1#![doc = "MAVLink common dialect."]
2#![doc = ""]
3#![doc = "This file was automatically generated, do not edit."]
4#[cfg(feature = "arbitrary")]
5use arbitrary::Arbitrary;
6#[allow(unused_imports)]
7use bitflags::bitflags;
8use mavlink_core::{bytes::Bytes, bytes_mut::BytesMut, MavlinkVersion, Message, MessageData};
9#[allow(unused_imports)]
10use num_derive::FromPrimitive;
11#[allow(unused_imports)]
12use num_derive::ToPrimitive;
13#[allow(unused_imports)]
14use num_traits::FromPrimitive;
15#[allow(unused_imports)]
16use num_traits::ToPrimitive;
17#[cfg(feature = "serde")]
18use serde::{Deserialize, Serialize};
19#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
20#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21#[cfg_attr(feature = "serde", serde(tag = "type"))]
22#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23#[repr(u32)]
24#[doc = "Possible responses from a WIFI_CONFIG_AP message."]
25pub enum WifiConfigApResponse {
26 #[doc = "Undefined response. Likely an indicative of a system that doesn't support this request."]
27 WIFI_CONFIG_AP_RESPONSE_UNDEFINED = 0,
28 #[doc = "Changes accepted."]
29 WIFI_CONFIG_AP_RESPONSE_ACCEPTED = 1,
30 #[doc = "Changes rejected."]
31 WIFI_CONFIG_AP_RESPONSE_REJECTED = 2,
32 #[doc = "Invalid Mode."]
33 WIFI_CONFIG_AP_RESPONSE_MODE_ERROR = 3,
34 #[doc = "Invalid SSID."]
35 WIFI_CONFIG_AP_RESPONSE_SSID_ERROR = 4,
36 #[doc = "Invalid Password."]
37 WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR = 5,
38}
39impl WifiConfigApResponse {
40 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_RESPONSE_UNDEFINED;
41}
42impl Default for WifiConfigApResponse {
43 fn default() -> Self {
44 Self::DEFAULT
45 }
46}
47bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags."] pub struct GimbalManagerCapFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; # [doc = "Gimbal manager supports to point to a local position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL = 65536 ; # [doc = "Gimbal manager supports to point to a global latitude, longitude, altitude position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL = 131072 ; } }
48impl GimbalManagerCapFlags {
49 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT;
50}
51impl Default for GimbalManagerCapFlags {
52 fn default() -> Self {
53 Self::DEFAULT
54 }
55}
56#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
57#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
58#[cfg_attr(feature = "serde", serde(tag = "type"))]
59#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
60#[repr(u32)]
61#[doc = "Camera tracking modes"]
62pub enum CameraTrackingMode {
63 #[doc = "Not tracking"]
64 CAMERA_TRACKING_MODE_NONE = 0,
65 #[doc = "Target is a point"]
66 CAMERA_TRACKING_MODE_POINT = 1,
67 #[doc = "Target is a rectangle"]
68 CAMERA_TRACKING_MODE_RECTANGLE = 2,
69}
70impl CameraTrackingMode {
71 pub const DEFAULT: Self = Self::CAMERA_TRACKING_MODE_NONE;
72}
73impl Default for CameraTrackingMode {
74 fn default() -> Self {
75 Self::DEFAULT
76 }
77}
78#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
79#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
80#[cfg_attr(feature = "serde", serde(tag = "type"))]
81#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
82#[repr(u32)]
83#[doc = "Cellular network radio type"]
84pub enum CellularNetworkRadioType {
85 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0,
86 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1,
87 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2,
88 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3,
89 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4,
90}
91impl CellularNetworkRadioType {
92 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_RADIO_TYPE_NONE;
93}
94impl Default for CellularNetworkRadioType {
95 fn default() -> Self {
96 Self::DEFAULT
97 }
98}
99bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid."] pub struct AisFlags : u16 { # [doc = "1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m."] const AIS_FLAGS_POSITION_ACCURACY = 1 ; const AIS_FLAGS_VALID_COG = 2 ; const AIS_FLAGS_VALID_VELOCITY = 4 ; # [doc = "1 = Velocity over 52.5765m/s (102.2 knots)"] const AIS_FLAGS_HIGH_VELOCITY = 8 ; const AIS_FLAGS_VALID_TURN_RATE = 16 ; # [doc = "Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s"] const AIS_FLAGS_TURN_RATE_SIGN_ONLY = 32 ; const AIS_FLAGS_VALID_DIMENSIONS = 64 ; # [doc = "Distance to bow is larger than 511m"] const AIS_FLAGS_LARGE_BOW_DIMENSION = 128 ; # [doc = "Distance to stern is larger than 511m"] const AIS_FLAGS_LARGE_STERN_DIMENSION = 256 ; # [doc = "Distance to port side is larger than 63m"] const AIS_FLAGS_LARGE_PORT_DIMENSION = 512 ; # [doc = "Distance to starboard side is larger than 63m"] const AIS_FLAGS_LARGE_STARBOARD_DIMENSION = 1024 ; const AIS_FLAGS_VALID_CALLSIGN = 2048 ; const AIS_FLAGS_VALID_NAME = 4096 ; } }
100impl AisFlags {
101 pub const DEFAULT: Self = Self::AIS_FLAGS_POSITION_ACCURACY;
102}
103impl Default for AisFlags {
104 fn default() -> Self {
105 Self::DEFAULT
106 }
107}
108#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
109#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
110#[cfg_attr(feature = "serde", serde(tag = "type"))]
111#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
112#[repr(u32)]
113#[doc = "ADSB classification for the type of vehicle emitting the transponder signal"]
114pub enum AdsbEmitterType {
115 ADSB_EMITTER_TYPE_NO_INFO = 0,
116 ADSB_EMITTER_TYPE_LIGHT = 1,
117 ADSB_EMITTER_TYPE_SMALL = 2,
118 ADSB_EMITTER_TYPE_LARGE = 3,
119 ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4,
120 ADSB_EMITTER_TYPE_HEAVY = 5,
121 ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6,
122 ADSB_EMITTER_TYPE_ROTOCRAFT = 7,
123 ADSB_EMITTER_TYPE_UNASSIGNED = 8,
124 ADSB_EMITTER_TYPE_GLIDER = 9,
125 ADSB_EMITTER_TYPE_LIGHTER_AIR = 10,
126 ADSB_EMITTER_TYPE_PARACHUTE = 11,
127 ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12,
128 ADSB_EMITTER_TYPE_UNASSIGNED2 = 13,
129 ADSB_EMITTER_TYPE_UAV = 14,
130 ADSB_EMITTER_TYPE_SPACE = 15,
131 ADSB_EMITTER_TYPE_UNASSGINED3 = 16,
132 ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17,
133 ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18,
134 ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19,
135}
136impl AdsbEmitterType {
137 pub const DEFAULT: Self = Self::ADSB_EMITTER_TYPE_NO_INFO;
138}
139impl Default for AdsbEmitterType {
140 fn default() -> Self {
141 Self::DEFAULT
142 }
143}
144#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
145#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
146#[cfg_attr(feature = "serde", serde(tag = "type"))]
147#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
148#[repr(u32)]
149#[doc = "These flags encode the cellular network status"]
150pub enum CellularStatusFlag {
151 #[doc = "State unknown or not reportable."]
152 CELLULAR_STATUS_FLAG_UNKNOWN = 0,
153 #[doc = "Modem is unusable"]
154 CELLULAR_STATUS_FLAG_FAILED = 1,
155 #[doc = "Modem is being initialized"]
156 CELLULAR_STATUS_FLAG_INITIALIZING = 2,
157 #[doc = "Modem is locked"]
158 CELLULAR_STATUS_FLAG_LOCKED = 3,
159 #[doc = "Modem is not enabled and is powered down"]
160 CELLULAR_STATUS_FLAG_DISABLED = 4,
161 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state"]
162 CELLULAR_STATUS_FLAG_DISABLING = 5,
163 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state"]
164 CELLULAR_STATUS_FLAG_ENABLING = 6,
165 #[doc = "Modem is enabled and powered on but not registered with a network provider and not available for data connections"]
166 CELLULAR_STATUS_FLAG_ENABLED = 7,
167 #[doc = "Modem is searching for a network provider to register"]
168 CELLULAR_STATUS_FLAG_SEARCHING = 8,
169 #[doc = "Modem is registered with a network provider, and data connections and messaging may be available for use"]
170 CELLULAR_STATUS_FLAG_REGISTERED = 9,
171 #[doc = "Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated"]
172 CELLULAR_STATUS_FLAG_DISCONNECTING = 10,
173 #[doc = "Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered"]
174 CELLULAR_STATUS_FLAG_CONNECTING = 11,
175 #[doc = "One or more packet data bearers is active and connected"]
176 CELLULAR_STATUS_FLAG_CONNECTED = 12,
177}
178impl CellularStatusFlag {
179 pub const DEFAULT: Self = Self::CELLULAR_STATUS_FLAG_UNKNOWN;
180}
181impl Default for CellularStatusFlag {
182 fn default() -> Self {
183 Self::DEFAULT
184 }
185}
186bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "SERIAL_CONTROL flags (bitmask)"] pub struct SerialControlFlag : u8 { # [doc = "Set if this is a reply"] const SERIAL_CONTROL_FLAG_REPLY = 1 ; # [doc = "Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message"] const SERIAL_CONTROL_FLAG_RESPOND = 2 ; # [doc = "Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set"] const SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 ; # [doc = "Block on writes to the serial port"] const SERIAL_CONTROL_FLAG_BLOCKING = 8 ; # [doc = "Send multiple replies until port is drained"] const SERIAL_CONTROL_FLAG_MULTI = 16 ; } }
187impl SerialControlFlag {
188 pub const DEFAULT: Self = Self::SERIAL_CONTROL_FLAG_REPLY;
189}
190impl Default for SerialControlFlag {
191 fn default() -> Self {
192 Self::DEFAULT
193 }
194}
195bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] pub struct GpsInputIgnoreFlags : u16 { # [doc = "ignore altitude field"] const GPS_INPUT_IGNORE_FLAG_ALT = 1 ; # [doc = "ignore hdop field"] const GPS_INPUT_IGNORE_FLAG_HDOP = 2 ; # [doc = "ignore vdop field"] const GPS_INPUT_IGNORE_FLAG_VDOP = 4 ; # [doc = "ignore horizontal velocity field (vn and ve)"] const GPS_INPUT_IGNORE_FLAG_VEL_HORIZ = 8 ; # [doc = "ignore vertical velocity field (vd)"] const GPS_INPUT_IGNORE_FLAG_VEL_VERT = 16 ; # [doc = "ignore speed accuracy field"] const GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY = 32 ; # [doc = "ignore horizontal accuracy field"] const GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY = 64 ; # [doc = "ignore vertical accuracy field"] const GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY = 128 ; } }
196impl GpsInputIgnoreFlags {
197 pub const DEFAULT: Self = Self::GPS_INPUT_IGNORE_FLAG_ALT;
198}
199impl Default for GpsInputIgnoreFlags {
200 fn default() -> Self {
201 Self::DEFAULT
202 }
203}
204#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
205#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
206#[cfg_attr(feature = "serde", serde(tag = "type"))]
207#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
208#[repr(u32)]
209pub enum MavOdidIdType {
210 #[doc = "No type defined."]
211 MAV_ODID_ID_TYPE_NONE = 0,
212 #[doc = "Manufacturer Serial Number (ANSI/CTA-2063 format)."]
213 MAV_ODID_ID_TYPE_SERIAL_NUMBER = 1,
214 #[doc = "CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]."]
215 MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID = 2,
216 #[doc = "UTM (Unmanned Traffic Management) assigned UUID (RFC4122)."]
217 MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID = 3,
218 #[doc = "A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO."]
219 MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID = 4,
220}
221impl MavOdidIdType {
222 pub const DEFAULT: Self = Self::MAV_ODID_ID_TYPE_NONE;
223}
224impl Default for MavOdidIdType {
225 fn default() -> Self {
226 Self::DEFAULT
227 }
228}
229#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
230#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
231#[cfg_attr(feature = "serde", serde(tag = "type"))]
232#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
233#[repr(u32)]
234#[doc = "MAV FTP opcodes: <https://mavlink.io/en/services/ftp.html>"]
235pub enum MavFtpOpcode {
236 #[doc = "None. Ignored, always ACKed"]
237 MAV_FTP_OPCODE_NONE = 0,
238 #[doc = "TerminateSession: Terminates open Read session"]
239 MAV_FTP_OPCODE_TERMINATESESSION = 1,
240 #[doc = "ResetSessions: Terminates all open read sessions"]
241 MAV_FTP_OPCODE_RESETSESSION = 2,
242 #[doc = "ListDirectory. List files and directories in path from offset"]
243 MAV_FTP_OPCODE_LISTDIRECTORY = 3,
244 #[doc = "OpenFileRO: Opens file at path for reading, returns session"]
245 MAV_FTP_OPCODE_OPENFILERO = 4,
246 #[doc = "ReadFile: Reads size bytes from offset in session"]
247 MAV_FTP_OPCODE_READFILE = 5,
248 #[doc = "CreateFile: Creates file at path for writing, returns session"]
249 MAV_FTP_OPCODE_CREATEFILE = 6,
250 #[doc = "WriteFile: Writes size bytes to offset in session"]
251 MAV_FTP_OPCODE_WRITEFILE = 7,
252 #[doc = "RemoveFile: Remove file at path"]
253 MAV_FTP_OPCODE_REMOVEFILE = 8,
254 #[doc = "CreateDirectory: Creates directory at path"]
255 MAV_FTP_OPCODE_CREATEDIRECTORY = 9,
256 #[doc = "RemoveDirectory: Removes directory at path. The directory must be empty."]
257 MAV_FTP_OPCODE_REMOVEDIRECTORY = 10,
258 #[doc = "OpenFileWO: Opens file at path for writing, returns session"]
259 MAV_FTP_OPCODE_OPENFILEWO = 11,
260 #[doc = "TruncateFile: Truncate file at path to offset length"]
261 MAV_FTP_OPCODE_TRUNCATEFILE = 12,
262 #[doc = "Rename: Rename path1 to path2"]
263 MAV_FTP_OPCODE_RENAME = 13,
264 #[doc = "CalcFileCRC32: Calculate CRC32 for file at path"]
265 MAV_FTP_OPCODE_CALCFILECRC = 14,
266 #[doc = "BurstReadFile: Burst download session file"]
267 MAV_FTP_OPCODE_BURSTREADFILE = 15,
268 #[doc = "ACK: ACK response"]
269 MAV_FTP_OPCODE_ACK = 128,
270 #[doc = "NAK: NAK response"]
271 MAV_FTP_OPCODE_NAK = 129,
272}
273impl MavFtpOpcode {
274 pub const DEFAULT: Self = Self::MAV_FTP_OPCODE_NONE;
275}
276impl Default for MavFtpOpcode {
277 fn default() -> Self {
278 Self::DEFAULT
279 }
280}
281#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
282#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
283#[cfg_attr(feature = "serde", serde(tag = "type"))]
284#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
285#[repr(u32)]
286#[doc = "Result of mission operation (in a MISSION_ACK message)."]
287pub enum MavMissionResult {
288 #[doc = "mission accepted OK"]
289 MAV_MISSION_ACCEPTED = 0,
290 #[doc = "Generic error / not accepting mission commands at all right now."]
291 MAV_MISSION_ERROR = 1,
292 #[doc = "Coordinate frame is not supported."]
293 MAV_MISSION_UNSUPPORTED_FRAME = 2,
294 #[doc = "Command is not supported."]
295 MAV_MISSION_UNSUPPORTED = 3,
296 #[doc = "Mission items exceed storage space."]
297 MAV_MISSION_NO_SPACE = 4,
298 #[doc = "One of the parameters has an invalid value."]
299 MAV_MISSION_INVALID = 5,
300 #[doc = "param1 has an invalid value."]
301 MAV_MISSION_INVALID_PARAM1 = 6,
302 #[doc = "param2 has an invalid value."]
303 MAV_MISSION_INVALID_PARAM2 = 7,
304 #[doc = "param3 has an invalid value."]
305 MAV_MISSION_INVALID_PARAM3 = 8,
306 #[doc = "param4 has an invalid value."]
307 MAV_MISSION_INVALID_PARAM4 = 9,
308 #[doc = "x / param5 has an invalid value."]
309 MAV_MISSION_INVALID_PARAM5_X = 10,
310 #[doc = "y / param6 has an invalid value."]
311 MAV_MISSION_INVALID_PARAM6_Y = 11,
312 #[doc = "z / param7 has an invalid value."]
313 MAV_MISSION_INVALID_PARAM7 = 12,
314 #[doc = "Mission item received out of sequence"]
315 MAV_MISSION_INVALID_SEQUENCE = 13,
316 #[doc = "Not accepting any mission commands from this communication partner."]
317 MAV_MISSION_DENIED = 14,
318 #[doc = "Current mission operation cancelled (e.g. mission upload, mission download)."]
319 MAV_MISSION_OPERATION_CANCELLED = 15,
320}
321impl MavMissionResult {
322 pub const DEFAULT: Self = Self::MAV_MISSION_ACCEPTED;
323}
324impl Default for MavMissionResult {
325 fn default() -> Self {
326 Self::DEFAULT
327 }
328}
329#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
330#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
331#[cfg_attr(feature = "serde", serde(tag = "type"))]
332#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
333#[repr(u32)]
334#[doc = "Direction of VTOL transition"]
335pub enum VtolTransitionHeading {
336 #[doc = "Respect the heading configuration of the vehicle."]
337 VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT = 0,
338 #[doc = "Use the heading pointing towards the next waypoint."]
339 VTOL_TRANSITION_HEADING_NEXT_WAYPOINT = 1,
340 #[doc = "Use the heading on takeoff (while sitting on the ground)."]
341 VTOL_TRANSITION_HEADING_TAKEOFF = 2,
342 #[doc = "Use the specified heading in parameter 4."]
343 VTOL_TRANSITION_HEADING_SPECIFIED = 3,
344 #[doc = "Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active)."]
345 VTOL_TRANSITION_HEADING_ANY = 4,
346}
347impl VtolTransitionHeading {
348 pub const DEFAULT: Self = Self::VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT;
349}
350impl Default for VtolTransitionHeading {
351 fn default() -> Self {
352 Self::DEFAULT
353 }
354}
355bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability."] pub struct MavProtocolCapability : u64 { # [doc = "Autopilot supports the MISSION_ITEM float message type. Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead."] const MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 ; # [doc = "Autopilot supports the new param float message type."] const MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 ; # [doc = "Autopilot supports MISSION_ITEM_INT scaled integer message type. Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated)."] const MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 ; # [doc = "Autopilot supports COMMAND_INT scaled integer message type."] const MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 ; # [doc = "Parameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE = 16 ; # [doc = "Autopilot supports the File Transfer Protocol v1: <https://mavlink.io/en/services/ftp.html>."] const MAV_PROTOCOL_CAPABILITY_FTP = 32 ; # [doc = "Autopilot supports commanding attitude offboard."] const MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 ; # [doc = "Autopilot supports commanding position and velocity targets in local NED frame."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 ; # [doc = "Autopilot supports commanding position and velocity targets in global scaled integers."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 ; # [doc = "Autopilot supports terrain protocol / data handling."] const MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED3 = 1024 ; # [doc = "Autopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination)."] const MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 ; # [doc = "Autopilot supports onboard compass calibration."] const MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 ; # [doc = "Autopilot supports MAVLink version 2."] const MAV_PROTOCOL_CAPABILITY_MAVLINK2 = 8192 ; # [doc = "Autopilot supports mission fence protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_FENCE = 16384 ; # [doc = "Autopilot supports mission rally point protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_RALLY = 32768 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED2 = 65536 ; # [doc = "Parameter protocol uses C-cast of parameter values to set the param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST = 131072 ; # [doc = "This component implements/is a gimbal manager. This means the GIMBAL_MANAGER_INFORMATION, and other messages can be requested."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_IMPLEMENTS_GIMBAL_MANAGER = 262144 ; # [doc = "Component supports locking control to a particular GCS independent of its system (via MAV_CMD_REQUEST_OPERATOR_CONTROL)."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_ACCEPTS_GCS_CONTROL = 524288 ; } }
356impl MavProtocolCapability {
357 pub const DEFAULT: Self = Self::MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
358}
359impl Default for MavProtocolCapability {
360 fn default() -> Self {
361 Self::DEFAULT
362 }
363}
364#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
365#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
366#[cfg_attr(feature = "serde", serde(tag = "type"))]
367#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
368#[repr(u32)]
369#[doc = "Enumeration of VTOL states"]
370pub enum MavVtolState {
371 #[doc = "MAV is not configured as VTOL"]
372 MAV_VTOL_STATE_UNDEFINED = 0,
373 #[doc = "VTOL is in transition from multicopter to fixed-wing"]
374 MAV_VTOL_STATE_TRANSITION_TO_FW = 1,
375 #[doc = "VTOL is in transition from fixed-wing to multicopter"]
376 MAV_VTOL_STATE_TRANSITION_TO_MC = 2,
377 #[doc = "VTOL is in multicopter state"]
378 MAV_VTOL_STATE_MC = 3,
379 #[doc = "VTOL is in fixed-wing state"]
380 MAV_VTOL_STATE_FW = 4,
381}
382impl MavVtolState {
383 pub const DEFAULT: Self = Self::MAV_VTOL_STATE_UNDEFINED;
384}
385impl Default for MavVtolState {
386 fn default() -> Self {
387 Self::DEFAULT
388 }
389}
390#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
391#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
392#[cfg_attr(feature = "serde", serde(tag = "type"))]
393#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
394#[repr(u32)]
395#[doc = "These flags are used to diagnose the failure state of CELLULAR_STATUS"]
396pub enum CellularNetworkFailedReason {
397 #[doc = "No error"]
398 CELLULAR_NETWORK_FAILED_REASON_NONE = 0,
399 #[doc = "Error state is unknown"]
400 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN = 1,
401 #[doc = "SIM is required for the modem but missing"]
402 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING = 2,
403 #[doc = "SIM is available, but not usable for connection"]
404 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR = 3,
405}
406impl CellularNetworkFailedReason {
407 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_FAILED_REASON_NONE;
408}
409impl Default for CellularNetworkFailedReason {
410 fn default() -> Self {
411 Self::DEFAULT
412 }
413}
414#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
415#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
416#[cfg_attr(feature = "serde", serde(tag = "type"))]
417#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
418#[repr(u32)]
419pub enum MavOdidOperatorIdType {
420 #[doc = "CAA (Civil Aviation Authority) registered operator ID."]
421 MAV_ODID_OPERATOR_ID_TYPE_CAA = 0,
422}
423impl MavOdidOperatorIdType {
424 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_ID_TYPE_CAA;
425}
426impl Default for MavOdidOperatorIdType {
427 fn default() -> Self {
428 Self::DEFAULT
429 }
430}
431#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
432#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
433#[cfg_attr(feature = "serde", serde(tag = "type"))]
434#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
435#[repr(u32)]
436#[doc = "List of possible units where failures can be injected."]
437pub enum FailureUnit {
438 FAILURE_UNIT_SENSOR_GYRO = 0,
439 FAILURE_UNIT_SENSOR_ACCEL = 1,
440 FAILURE_UNIT_SENSOR_MAG = 2,
441 FAILURE_UNIT_SENSOR_BARO = 3,
442 FAILURE_UNIT_SENSOR_GPS = 4,
443 FAILURE_UNIT_SENSOR_OPTICAL_FLOW = 5,
444 FAILURE_UNIT_SENSOR_VIO = 6,
445 FAILURE_UNIT_SENSOR_DISTANCE_SENSOR = 7,
446 FAILURE_UNIT_SENSOR_AIRSPEED = 8,
447 FAILURE_UNIT_SYSTEM_BATTERY = 100,
448 FAILURE_UNIT_SYSTEM_MOTOR = 101,
449 FAILURE_UNIT_SYSTEM_SERVO = 102,
450 FAILURE_UNIT_SYSTEM_AVOIDANCE = 103,
451 FAILURE_UNIT_SYSTEM_RC_SIGNAL = 104,
452 FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL = 105,
453}
454impl FailureUnit {
455 pub const DEFAULT: Self = Self::FAILURE_UNIT_SENSOR_GYRO;
456}
457impl Default for FailureUnit {
458 fn default() -> Self {
459 Self::DEFAULT
460 }
461}
462#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
463#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
464#[cfg_attr(feature = "serde", serde(tag = "type"))]
465#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
466#[repr(u32)]
467#[doc = "Fence types to enable or disable when using MAV_CMD_DO_FENCE_ENABLE. Note that at least one of these flags must be set in MAV_CMD_DO_FENCE_ENABLE.param2. If none are set, the flight stack will ignore the field and enable/disable its default set of fences (usually all of them)."]
468pub enum FenceType {
469 #[doc = "Maximum altitude fence"]
470 FENCE_TYPE_ALT_MAX = 1,
471 #[doc = "Circle fence"]
472 FENCE_TYPE_CIRCLE = 2,
473 #[doc = "Polygon fence"]
474 FENCE_TYPE_POLYGON = 4,
475 #[doc = "Minimum altitude fence"]
476 FENCE_TYPE_ALT_MIN = 8,
477}
478impl FenceType {
479 pub const DEFAULT: Self = Self::FENCE_TYPE_ALT_MAX;
480}
481impl Default for FenceType {
482 fn default() -> Self {
483 Self::DEFAULT
484 }
485}
486bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE)."] pub struct StorageUsageFlag : u8 { # [doc = "Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported)."] const STORAGE_USAGE_FLAG_SET = 1 ; # [doc = "Storage for saving photos."] const STORAGE_USAGE_FLAG_PHOTO = 2 ; # [doc = "Storage for saving videos."] const STORAGE_USAGE_FLAG_VIDEO = 4 ; # [doc = "Storage for saving logs."] const STORAGE_USAGE_FLAG_LOGS = 8 ; } }
487impl StorageUsageFlag {
488 pub const DEFAULT: Self = Self::STORAGE_USAGE_FLAG_SET;
489}
490impl Default for StorageUsageFlag {
491 fn default() -> Self {
492 Self::DEFAULT
493 }
494}
495#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
496#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
497#[cfg_attr(feature = "serde", serde(tag = "type"))]
498#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
499#[repr(u32)]
500pub enum MavOdidVerAcc {
501 #[doc = "The vertical accuracy is unknown."]
502 MAV_ODID_VER_ACC_UNKNOWN = 0,
503 #[doc = "The vertical accuracy is smaller than 150 meter."]
504 MAV_ODID_VER_ACC_150_METER = 1,
505 #[doc = "The vertical accuracy is smaller than 45 meter."]
506 MAV_ODID_VER_ACC_45_METER = 2,
507 #[doc = "The vertical accuracy is smaller than 25 meter."]
508 MAV_ODID_VER_ACC_25_METER = 3,
509 #[doc = "The vertical accuracy is smaller than 10 meter."]
510 MAV_ODID_VER_ACC_10_METER = 4,
511 #[doc = "The vertical accuracy is smaller than 3 meter."]
512 MAV_ODID_VER_ACC_3_METER = 5,
513 #[doc = "The vertical accuracy is smaller than 1 meter."]
514 MAV_ODID_VER_ACC_1_METER = 6,
515}
516impl MavOdidVerAcc {
517 pub const DEFAULT: Self = Self::MAV_ODID_VER_ACC_UNKNOWN;
518}
519impl Default for MavOdidVerAcc {
520 fn default() -> Self {
521 Self::DEFAULT
522 }
523}
524#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
525#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
526#[cfg_attr(feature = "serde", serde(tag = "type"))]
527#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
528#[repr(u32)]
529#[doc = "Possible safety switch states."]
530pub enum SafetySwitchState {
531 #[doc = "Safety switch is engaged and vehicle should be safe to approach."]
532 SAFETY_SWITCH_STATE_SAFE = 0,
533 #[doc = "Safety switch is NOT engaged and motors, propellers and other actuators should be considered active."]
534 SAFETY_SWITCH_STATE_DANGEROUS = 1,
535}
536impl SafetySwitchState {
537 pub const DEFAULT: Self = Self::SAFETY_SWITCH_STATE_SAFE;
538}
539impl Default for SafetySwitchState {
540 fn default() -> Self {
541 Self::DEFAULT
542 }
543}
544#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
545#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
546#[cfg_attr(feature = "serde", serde(tag = "type"))]
547#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
548#[repr(u32)]
549#[doc = "RTK GPS baseline coordinate system, used for RTK corrections"]
550pub enum RtkBaselineCoordinateSystem {
551 #[doc = "Earth-centered, Earth-fixed"]
552 RTK_BASELINE_COORDINATE_SYSTEM_ECEF = 0,
553 #[doc = "RTK basestation centered, north, east, down"]
554 RTK_BASELINE_COORDINATE_SYSTEM_NED = 1,
555}
556impl RtkBaselineCoordinateSystem {
557 pub const DEFAULT: Self = Self::RTK_BASELINE_COORDINATE_SYSTEM_ECEF;
558}
559impl Default for RtkBaselineCoordinateSystem {
560 fn default() -> Self {
561 Self::DEFAULT
562 }
563}
564#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
565#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
566#[cfg_attr(feature = "serde", serde(tag = "type"))]
567#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
568#[repr(u32)]
569#[doc = "Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - \"GLOBAL\": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with \"GLOBAL\": - \"RELATIVE_ALT\": Altitude is relative to the vehicle home position rather than MSL. - \"TERRAIN_ALT\": Altitude is relative to ground level rather than MSL. - \"INT\": Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - \"LOCAL\": Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator (\"EKF\"). - \"BODY\": Origin of local frame travels with the vehicle. NOTE, \"BODY\" does NOT indicate alignment of frame axis with vehicle attitude. - \"OFFSET\": Deprecated synonym for \"BODY\" (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED)."]
570pub enum MavFrame {
571 #[doc = "Global (WGS84) coordinate frame + altitude relative to mean sea level (MSL)."]
572 MAV_FRAME_GLOBAL = 0,
573 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth."]
574 MAV_FRAME_LOCAL_NED = 1,
575 #[doc = "NOT a coordinate frame, indicates a mission command."]
576 MAV_FRAME_MISSION = 2,
577 #[doc = "Global (WGS84) coordinate frame + altitude relative to the home position."]
578 MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
579 #[doc = "ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth."]
580 MAV_FRAME_LOCAL_ENU = 4,
581 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to mean sea level (MSL)."]
582 MAV_FRAME_GLOBAL_INT = 5,
583 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to the home position."]
584 MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6,
585 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle."]
586 MAV_FRAME_LOCAL_OFFSET_NED = 7,
587 #[doc = "Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values."]
588 MAV_FRAME_BODY_NED = 8,
589 #[doc = "This is the same as MAV_FRAME_BODY_FRD."]
590 MAV_FRAME_BODY_OFFSET_NED = 9,
591 #[doc = "Global (WGS84) coordinate frame with AGL altitude (altitude at ground level)."]
592 MAV_FRAME_GLOBAL_TERRAIN_ALT = 10,
593 #[doc = "Global (WGS84) coordinate frame (scaled) with AGL altitude (altitude at ground level)."]
594 MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11,
595 #[doc = "FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle."]
596 MAV_FRAME_BODY_FRD = 12,
597 #[doc = "MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up)."]
598 MAV_FRAME_RESERVED_13 = 13,
599 #[doc = "MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down)."]
600 MAV_FRAME_RESERVED_14 = 14,
601 #[doc = "MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up)."]
602 MAV_FRAME_RESERVED_15 = 15,
603 #[doc = "MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down)."]
604 MAV_FRAME_RESERVED_16 = 16,
605 #[doc = "MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up)."]
606 MAV_FRAME_RESERVED_17 = 17,
607 #[doc = "MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down)."]
608 MAV_FRAME_RESERVED_18 = 18,
609 #[doc = "MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up)."]
610 MAV_FRAME_RESERVED_19 = 19,
611 #[doc = "FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
612 MAV_FRAME_LOCAL_FRD = 20,
613 #[doc = "FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
614 MAV_FRAME_LOCAL_FLU = 21,
615}
616impl MavFrame {
617 pub const DEFAULT: Self = Self::MAV_FRAME_GLOBAL;
618}
619impl Default for MavFrame {
620 fn default() -> Self {
621 Self::DEFAULT
622 }
623}
624#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
625#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
626#[cfg_attr(feature = "serde", serde(tag = "type"))]
627#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
628#[repr(u32)]
629#[doc = "Parachute actions. Trigger release and enable/disable auto-release."]
630pub enum ParachuteAction {
631 #[doc = "Disable auto-release of parachute (i.e. release triggered by crash detectors)."]
632 PARACHUTE_DISABLE = 0,
633 #[doc = "Enable auto-release of parachute."]
634 PARACHUTE_ENABLE = 1,
635 #[doc = "Release parachute and kill motors."]
636 PARACHUTE_RELEASE = 2,
637}
638impl ParachuteAction {
639 pub const DEFAULT: Self = Self::PARACHUTE_DISABLE;
640}
641impl Default for ParachuteAction {
642 fn default() -> Self {
643 Self::DEFAULT
644 }
645}
646#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
647#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
648#[cfg_attr(feature = "serde", serde(tag = "type"))]
649#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
650#[repr(u32)]
651#[doc = "Supported component metadata types. These are used in the \"general\" metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages."]
652pub enum CompMetadataType {
653 #[doc = "General information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI."]
654 COMP_METADATA_TYPE_GENERAL = 0,
655 #[doc = "Parameter meta data."]
656 COMP_METADATA_TYPE_PARAMETER = 1,
657 #[doc = "Meta data that specifies which commands and command parameters the vehicle supports. (WIP)"]
658 COMP_METADATA_TYPE_COMMANDS = 2,
659 #[doc = "Meta data that specifies external non-MAVLink peripherals."]
660 COMP_METADATA_TYPE_PERIPHERALS = 3,
661 #[doc = "Meta data for the events interface."]
662 COMP_METADATA_TYPE_EVENTS = 4,
663 #[doc = "Meta data for actuator configuration (motors, servos and vehicle geometry) and testing."]
664 COMP_METADATA_TYPE_ACTUATORS = 5,
665}
666impl CompMetadataType {
667 pub const DEFAULT: Self = Self::COMP_METADATA_TYPE_GENERAL;
668}
669impl Default for CompMetadataType {
670 fn default() -> Self {
671 Self::DEFAULT
672 }
673}
674#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
675#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
676#[cfg_attr(feature = "serde", serde(tag = "type"))]
677#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
678#[repr(u32)]
679#[doc = "Aircraft-rated danger from this threat."]
680pub enum MavCollisionThreatLevel {
681 #[doc = "Not a threat"]
682 MAV_COLLISION_THREAT_LEVEL_NONE = 0,
683 #[doc = "Craft is mildly concerned about this threat"]
684 MAV_COLLISION_THREAT_LEVEL_LOW = 1,
685 #[doc = "Craft is panicking, and may take actions to avoid threat"]
686 MAV_COLLISION_THREAT_LEVEL_HIGH = 2,
687}
688impl MavCollisionThreatLevel {
689 pub const DEFAULT: Self = Self::MAV_COLLISION_THREAT_LEVEL_NONE;
690}
691impl Default for MavCollisionThreatLevel {
692 fn default() -> Self {
693 Self::DEFAULT
694 }
695}
696#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
697#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
698#[cfg_attr(feature = "serde", serde(tag = "type"))]
699#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
700#[repr(u32)]
701#[doc = "Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands."]
702pub enum ActuatorConfiguration {
703 #[doc = "Do nothing."]
704 ACTUATOR_CONFIGURATION_NONE = 0,
705 #[doc = "Command the actuator to beep now."]
706 ACTUATOR_CONFIGURATION_BEEP = 1,
707 #[doc = "Permanently set the actuator (ESC) to 3D mode (reversible thrust)."]
708 ACTUATOR_CONFIGURATION_3D_MODE_ON = 2,
709 #[doc = "Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust)."]
710 ACTUATOR_CONFIGURATION_3D_MODE_OFF = 3,
711 #[doc = "Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise)."]
712 ACTUATOR_CONFIGURATION_SPIN_DIRECTION1 = 4,
713 #[doc = "Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1)."]
714 ACTUATOR_CONFIGURATION_SPIN_DIRECTION2 = 5,
715}
716impl ActuatorConfiguration {
717 pub const DEFAULT: Self = Self::ACTUATOR_CONFIGURATION_NONE;
718}
719impl Default for ActuatorConfiguration {
720 fn default() -> Self {
721 Self::DEFAULT
722 }
723}
724#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
725#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
726#[cfg_attr(feature = "serde", serde(tag = "type"))]
727#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
728#[repr(u32)]
729#[doc = "Type of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
730pub enum AisType {
731 #[doc = "Not available (default)."]
732 AIS_TYPE_UNKNOWN = 0,
733 AIS_TYPE_RESERVED_1 = 1,
734 AIS_TYPE_RESERVED_2 = 2,
735 AIS_TYPE_RESERVED_3 = 3,
736 AIS_TYPE_RESERVED_4 = 4,
737 AIS_TYPE_RESERVED_5 = 5,
738 AIS_TYPE_RESERVED_6 = 6,
739 AIS_TYPE_RESERVED_7 = 7,
740 AIS_TYPE_RESERVED_8 = 8,
741 AIS_TYPE_RESERVED_9 = 9,
742 AIS_TYPE_RESERVED_10 = 10,
743 AIS_TYPE_RESERVED_11 = 11,
744 AIS_TYPE_RESERVED_12 = 12,
745 AIS_TYPE_RESERVED_13 = 13,
746 AIS_TYPE_RESERVED_14 = 14,
747 AIS_TYPE_RESERVED_15 = 15,
748 AIS_TYPE_RESERVED_16 = 16,
749 AIS_TYPE_RESERVED_17 = 17,
750 AIS_TYPE_RESERVED_18 = 18,
751 AIS_TYPE_RESERVED_19 = 19,
752 #[doc = "Wing In Ground effect."]
753 AIS_TYPE_WIG = 20,
754 AIS_TYPE_WIG_HAZARDOUS_A = 21,
755 AIS_TYPE_WIG_HAZARDOUS_B = 22,
756 AIS_TYPE_WIG_HAZARDOUS_C = 23,
757 AIS_TYPE_WIG_HAZARDOUS_D = 24,
758 AIS_TYPE_WIG_RESERVED_1 = 25,
759 AIS_TYPE_WIG_RESERVED_2 = 26,
760 AIS_TYPE_WIG_RESERVED_3 = 27,
761 AIS_TYPE_WIG_RESERVED_4 = 28,
762 AIS_TYPE_WIG_RESERVED_5 = 29,
763 AIS_TYPE_FISHING = 30,
764 AIS_TYPE_TOWING = 31,
765 #[doc = "Towing: length exceeds 200m or breadth exceeds 25m."]
766 AIS_TYPE_TOWING_LARGE = 32,
767 #[doc = "Dredging or other underwater ops."]
768 AIS_TYPE_DREDGING = 33,
769 AIS_TYPE_DIVING = 34,
770 AIS_TYPE_MILITARY = 35,
771 AIS_TYPE_SAILING = 36,
772 AIS_TYPE_PLEASURE = 37,
773 AIS_TYPE_RESERVED_20 = 38,
774 AIS_TYPE_RESERVED_21 = 39,
775 #[doc = "High Speed Craft."]
776 AIS_TYPE_HSC = 40,
777 AIS_TYPE_HSC_HAZARDOUS_A = 41,
778 AIS_TYPE_HSC_HAZARDOUS_B = 42,
779 AIS_TYPE_HSC_HAZARDOUS_C = 43,
780 AIS_TYPE_HSC_HAZARDOUS_D = 44,
781 AIS_TYPE_HSC_RESERVED_1 = 45,
782 AIS_TYPE_HSC_RESERVED_2 = 46,
783 AIS_TYPE_HSC_RESERVED_3 = 47,
784 AIS_TYPE_HSC_RESERVED_4 = 48,
785 AIS_TYPE_HSC_UNKNOWN = 49,
786 AIS_TYPE_PILOT = 50,
787 #[doc = "Search And Rescue vessel."]
788 AIS_TYPE_SAR = 51,
789 AIS_TYPE_TUG = 52,
790 AIS_TYPE_PORT_TENDER = 53,
791 #[doc = "Anti-pollution equipment."]
792 AIS_TYPE_ANTI_POLLUTION = 54,
793 AIS_TYPE_LAW_ENFORCEMENT = 55,
794 AIS_TYPE_SPARE_LOCAL_1 = 56,
795 AIS_TYPE_SPARE_LOCAL_2 = 57,
796 AIS_TYPE_MEDICAL_TRANSPORT = 58,
797 #[doc = "Noncombatant ship according to RR Resolution No. 18."]
798 AIS_TYPE_NONECOMBATANT = 59,
799 AIS_TYPE_PASSENGER = 60,
800 AIS_TYPE_PASSENGER_HAZARDOUS_A = 61,
801 AIS_TYPE_PASSENGER_HAZARDOUS_B = 62,
802 AIS_TYPE_PASSENGER_HAZARDOUS_C = 63,
803 AIS_TYPE_PASSENGER_HAZARDOUS_D = 64,
804 AIS_TYPE_PASSENGER_RESERVED_1 = 65,
805 AIS_TYPE_PASSENGER_RESERVED_2 = 66,
806 AIS_TYPE_PASSENGER_RESERVED_3 = 67,
807 AIS_TYPE_PASSENGER_RESERVED_4 = 68,
808 AIS_TYPE_PASSENGER_UNKNOWN = 69,
809 AIS_TYPE_CARGO = 70,
810 AIS_TYPE_CARGO_HAZARDOUS_A = 71,
811 AIS_TYPE_CARGO_HAZARDOUS_B = 72,
812 AIS_TYPE_CARGO_HAZARDOUS_C = 73,
813 AIS_TYPE_CARGO_HAZARDOUS_D = 74,
814 AIS_TYPE_CARGO_RESERVED_1 = 75,
815 AIS_TYPE_CARGO_RESERVED_2 = 76,
816 AIS_TYPE_CARGO_RESERVED_3 = 77,
817 AIS_TYPE_CARGO_RESERVED_4 = 78,
818 AIS_TYPE_CARGO_UNKNOWN = 79,
819 AIS_TYPE_TANKER = 80,
820 AIS_TYPE_TANKER_HAZARDOUS_A = 81,
821 AIS_TYPE_TANKER_HAZARDOUS_B = 82,
822 AIS_TYPE_TANKER_HAZARDOUS_C = 83,
823 AIS_TYPE_TANKER_HAZARDOUS_D = 84,
824 AIS_TYPE_TANKER_RESERVED_1 = 85,
825 AIS_TYPE_TANKER_RESERVED_2 = 86,
826 AIS_TYPE_TANKER_RESERVED_3 = 87,
827 AIS_TYPE_TANKER_RESERVED_4 = 88,
828 AIS_TYPE_TANKER_UNKNOWN = 89,
829 AIS_TYPE_OTHER = 90,
830 AIS_TYPE_OTHER_HAZARDOUS_A = 91,
831 AIS_TYPE_OTHER_HAZARDOUS_B = 92,
832 AIS_TYPE_OTHER_HAZARDOUS_C = 93,
833 AIS_TYPE_OTHER_HAZARDOUS_D = 94,
834 AIS_TYPE_OTHER_RESERVED_1 = 95,
835 AIS_TYPE_OTHER_RESERVED_2 = 96,
836 AIS_TYPE_OTHER_RESERVED_3 = 97,
837 AIS_TYPE_OTHER_RESERVED_4 = 98,
838 AIS_TYPE_OTHER_UNKNOWN = 99,
839}
840impl AisType {
841 pub const DEFAULT: Self = Self::AIS_TYPE_UNKNOWN;
842}
843impl Default for AisType {
844 fn default() -> Self {
845 Self::DEFAULT
846 }
847}
848#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
849#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
850#[cfg_attr(feature = "serde", serde(tag = "type"))]
851#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
852#[repr(u32)]
853#[doc = "Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight."]
854pub enum MavBatteryMode {
855 #[doc = "Battery mode not supported/unknown battery mode/normal operation."]
856 MAV_BATTERY_MODE_UNKNOWN = 0,
857 #[doc = "Battery is auto discharging (towards storage level)."]
858 MAV_BATTERY_MODE_AUTO_DISCHARGING = 1,
859 #[doc = "Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits)."]
860 MAV_BATTERY_MODE_HOT_SWAP = 2,
861}
862impl MavBatteryMode {
863 pub const DEFAULT: Self = Self::MAV_BATTERY_MODE_UNKNOWN;
864}
865impl Default for MavBatteryMode {
866 fn default() -> Self {
867 Self::DEFAULT
868 }
869}
870bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly)."] pub struct MavGeneratorStatusFlag : u64 { # [doc = "Generator is off."] const MAV_GENERATOR_STATUS_FLAG_OFF = 1 ; # [doc = "Generator is ready to start generating power."] const MAV_GENERATOR_STATUS_FLAG_READY = 2 ; # [doc = "Generator is generating power."] const MAV_GENERATOR_STATUS_FLAG_GENERATING = 4 ; # [doc = "Generator is charging the batteries (generating enough power to charge and provide the load)."] const MAV_GENERATOR_STATUS_FLAG_CHARGING = 8 ; # [doc = "Generator is operating at a reduced maximum power."] const MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER = 16 ; # [doc = "Generator is providing the maximum output."] const MAV_GENERATOR_STATUS_FLAG_MAXPOWER = 32 ; # [doc = "Generator is near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING = 64 ; # [doc = "Generator hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT = 128 ; # [doc = "Power electronics are near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = 256 ; # [doc = "Power electronics hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = 512 ; # [doc = "Power electronics experienced a fault and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT = 1024 ; # [doc = "The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening."] const MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT = 2048 ; # [doc = "Generator controller having communication problems."] const MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING = 4096 ; # [doc = "Power electronic or generator cooling system error."] const MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING = 8192 ; # [doc = "Generator controller power rail experienced a fault."] const MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT = 16384 ; # [doc = "Generator controller exceeded the overcurrent threshold and shutdown to prevent damage."] const MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT = 32768 ; # [doc = "Generator controller detected a high current going into the batteries and shutdown to prevent battery damage."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = 65536 ; # [doc = "Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating."] const MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT = 131072 ; # [doc = "Batteries are under voltage (generator will not start)."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = 262144 ; # [doc = "Generator start is inhibited by e.g. a safety switch."] const MAV_GENERATOR_STATUS_FLAG_START_INHIBITED = 524288 ; # [doc = "Generator requires maintenance."] const MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED = 1048576 ; # [doc = "Generator is not ready to generate yet."] const MAV_GENERATOR_STATUS_FLAG_WARMING_UP = 2097152 ; # [doc = "Generator is idle."] const MAV_GENERATOR_STATUS_FLAG_IDLE = 4194304 ; } }
871impl MavGeneratorStatusFlag {
872 pub const DEFAULT: Self = Self::MAV_GENERATOR_STATUS_FLAG_OFF;
873}
874impl Default for MavGeneratorStatusFlag {
875 fn default() -> Self {
876 Self::DEFAULT
877 }
878}
879#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
880#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
881#[cfg_attr(feature = "serde", serde(tag = "type"))]
882#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
883#[repr(u32)]
884pub enum MavTunnelPayloadType {
885 #[doc = "Encoding of payload unknown."]
886 MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN = 0,
887 #[doc = "Registered for STorM32 gimbal controller."]
888 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 = 200,
889 #[doc = "Registered for STorM32 gimbal controller."]
890 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 = 201,
891 #[doc = "Registered for STorM32 gimbal controller."]
892 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 = 202,
893 #[doc = "Registered for STorM32 gimbal controller."]
894 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 = 203,
895 #[doc = "Registered for STorM32 gimbal controller."]
896 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 = 204,
897 #[doc = "Registered for STorM32 gimbal controller."]
898 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 = 205,
899 #[doc = "Registered for STorM32 gimbal controller."]
900 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 = 206,
901 #[doc = "Registered for STorM32 gimbal controller."]
902 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 = 207,
903 #[doc = "Registered for STorM32 gimbal controller."]
904 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 = 208,
905 #[doc = "Registered for STorM32 gimbal controller."]
906 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 = 209,
907 #[doc = "Registered for ModalAI remote OSD protocol."]
908 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_REMOTE_OSD = 210,
909 #[doc = "Registered for ModalAI ESC UART passthru protocol."]
910 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_ESC_UART_PASSTHRU = 211,
911 #[doc = "Registered for ModalAI vendor use."]
912 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_IO_UART_PASSTHRU = 212,
913}
914impl MavTunnelPayloadType {
915 pub const DEFAULT: Self = Self::MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN;
916}
917impl Default for MavTunnelPayloadType {
918 fn default() -> Self {
919 Self::DEFAULT
920 }
921}
922#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
923#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
924#[cfg_attr(feature = "serde", serde(tag = "type"))]
925#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
926#[repr(u32)]
927#[doc = "States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles."]
928pub enum MissionState {
929 #[doc = "The mission status reporting is not supported."]
930 MISSION_STATE_UNKNOWN = 0,
931 #[doc = "No mission on the vehicle."]
932 MISSION_STATE_NO_MISSION = 1,
933 #[doc = "Mission has not started. This is the case after a mission has uploaded but not yet started executing."]
934 MISSION_STATE_NOT_STARTED = 2,
935 #[doc = "Mission is active, and will execute mission items when in auto mode."]
936 MISSION_STATE_ACTIVE = 3,
937 #[doc = "Mission is paused when in auto mode."]
938 MISSION_STATE_PAUSED = 4,
939 #[doc = "Mission has executed all mission items."]
940 MISSION_STATE_COMPLETE = 5,
941}
942impl MissionState {
943 pub const DEFAULT: Self = Self::MISSION_STATE_UNKNOWN;
944}
945impl Default for MissionState {
946 fn default() -> Self {
947 Self::DEFAULT
948 }
949}
950bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Mode properties."] pub struct MavModeProperty : u32 { # [doc = "If set, this mode is an advanced mode. For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. A GCS can optionally use this flag to configure the UI for its intended users."] const MAV_MODE_PROPERTY_ADVANCED = 1 ; # [doc = "If set, this mode should not be added to the list of selectable modes. The mode might still be selected by the FC directly (for example as part of a failsafe)."] const MAV_MODE_PROPERTY_NOT_USER_SELECTABLE = 2 ; # [doc = "If set, this mode is automatically controlled (it may use but does not require a manual controller). If unset the mode is a assumed to require user input (be a manual mode)."] const MAV_MODE_PROPERTY_AUTO_MODE = 4 ; } }
951impl MavModeProperty {
952 pub const DEFAULT: Self = Self::MAV_MODE_PROPERTY_ADVANCED;
953}
954impl Default for MavModeProperty {
955 fn default() -> Self {
956 Self::DEFAULT
957 }
958}
959bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS."] pub struct GimbalManagerFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_FLAGS_RETRACT."] const GIMBAL_MANAGER_FLAGS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_NEUTRAL."] const GIMBAL_MANAGER_FLAGS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK."] const GIMBAL_MANAGER_FLAGS_ROLL_LOCK = 4 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK."] const GIMBAL_MANAGER_FLAGS_PITCH_LOCK = 8 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK."] const GIMBAL_MANAGER_FLAGS_YAW_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE."] const GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_MIXED."] const GIMBAL_MANAGER_FLAGS_RC_MIXED = 512 ; } }
960impl GimbalManagerFlags {
961 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_FLAGS_RETRACT;
962}
963impl Default for GimbalManagerFlags {
964 fn default() -> Self {
965 Self::DEFAULT
966 }
967}
968#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
969#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
970#[cfg_attr(feature = "serde", serde(tag = "type"))]
971#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
972#[repr(u32)]
973#[doc = "Fuel types for use in FUEL_TYPE. Fuel types specify the units for the maximum, available and consumed fuel, and for the flow rates."]
974pub enum MavFuelType {
975 #[doc = "Not specified. Fuel levels are normalized (i.e. maximum is 1, and other levels are relative to 1)."]
976 MAV_FUEL_TYPE_UNKNOWN = 0,
977 #[doc = "A generic liquid fuel. Fuel levels are in millilitres (ml). Fuel rates are in millilitres/second."]
978 MAV_FUEL_TYPE_LIQUID = 1,
979 #[doc = "A gas tank. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s)."]
980 MAV_FUEL_TYPE_GAS = 2,
981}
982impl MavFuelType {
983 pub const DEFAULT: Self = Self::MAV_FUEL_TYPE_UNKNOWN;
984}
985impl Default for MavFuelType {
986 fn default() -> Self {
987 Self::DEFAULT
988 }
989}
990#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
991#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
992#[cfg_attr(feature = "serde", serde(tag = "type"))]
993#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
994#[repr(u32)]
995#[doc = "Focus types for MAV_CMD_SET_CAMERA_FOCUS"]
996pub enum SetFocusType {
997 #[doc = "Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity)."]
998 FOCUS_TYPE_STEP = 0,
999 #[doc = "Continuous normalized focus in/out rate until stopped. Range -1..1, negative: in, positive: out towards infinity, 0 to stop focusing. Other values should be clipped to the range."]
1000 FOCUS_TYPE_CONTINUOUS = 1,
1001 #[doc = "Focus value as proportion of full camera focus range (a value between 0.0 and 100.0)"]
1002 FOCUS_TYPE_RANGE = 2,
1003 #[doc = "Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)."]
1004 FOCUS_TYPE_METERS = 3,
1005 #[doc = "Focus automatically."]
1006 FOCUS_TYPE_AUTO = 4,
1007 #[doc = "Single auto focus. Mainly used for still pictures. Usually abbreviated as AF-S."]
1008 FOCUS_TYPE_AUTO_SINGLE = 5,
1009 #[doc = "Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C."]
1010 FOCUS_TYPE_AUTO_CONTINUOUS = 6,
1011}
1012impl SetFocusType {
1013 pub const DEFAULT: Self = Self::FOCUS_TYPE_STEP;
1014}
1015impl Default for SetFocusType {
1016 fn default() -> Self {
1017 Self::DEFAULT
1018 }
1019}
1020#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1021#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1022#[cfg_attr(feature = "serde", serde(tag = "type"))]
1023#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1024#[repr(u32)]
1025#[doc = "Enumeration of landed detector states"]
1026pub enum MavLandedState {
1027 #[doc = "MAV landed state is unknown"]
1028 MAV_LANDED_STATE_UNDEFINED = 0,
1029 #[doc = "MAV is landed (on ground)"]
1030 MAV_LANDED_STATE_ON_GROUND = 1,
1031 #[doc = "MAV is in air"]
1032 MAV_LANDED_STATE_IN_AIR = 2,
1033 #[doc = "MAV currently taking off"]
1034 MAV_LANDED_STATE_TAKEOFF = 3,
1035 #[doc = "MAV currently landing"]
1036 MAV_LANDED_STATE_LANDING = 4,
1037}
1038impl MavLandedState {
1039 pub const DEFAULT: Self = Self::MAV_LANDED_STATE_UNDEFINED;
1040}
1041impl Default for MavLandedState {
1042 fn default() -> Self {
1043 Self::DEFAULT
1044 }
1045}
1046#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1047#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1048#[cfg_attr(feature = "serde", serde(tag = "type"))]
1049#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1050#[repr(u32)]
1051pub enum MavOdidHorAcc {
1052 #[doc = "The horizontal accuracy is unknown."]
1053 MAV_ODID_HOR_ACC_UNKNOWN = 0,
1054 #[doc = "The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km."]
1055 MAV_ODID_HOR_ACC_10NM = 1,
1056 #[doc = "The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km."]
1057 MAV_ODID_HOR_ACC_4NM = 2,
1058 #[doc = "The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km."]
1059 MAV_ODID_HOR_ACC_2NM = 3,
1060 #[doc = "The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km."]
1061 MAV_ODID_HOR_ACC_1NM = 4,
1062 #[doc = "The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m."]
1063 MAV_ODID_HOR_ACC_0_5NM = 5,
1064 #[doc = "The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m."]
1065 MAV_ODID_HOR_ACC_0_3NM = 6,
1066 #[doc = "The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m."]
1067 MAV_ODID_HOR_ACC_0_1NM = 7,
1068 #[doc = "The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m."]
1069 MAV_ODID_HOR_ACC_0_05NM = 8,
1070 #[doc = "The horizontal accuracy is smaller than 30 meter."]
1071 MAV_ODID_HOR_ACC_30_METER = 9,
1072 #[doc = "The horizontal accuracy is smaller than 10 meter."]
1073 MAV_ODID_HOR_ACC_10_METER = 10,
1074 #[doc = "The horizontal accuracy is smaller than 3 meter."]
1075 MAV_ODID_HOR_ACC_3_METER = 11,
1076 #[doc = "The horizontal accuracy is smaller than 1 meter."]
1077 MAV_ODID_HOR_ACC_1_METER = 12,
1078}
1079impl MavOdidHorAcc {
1080 pub const DEFAULT: Self = Self::MAV_ODID_HOR_ACC_UNKNOWN;
1081}
1082impl Default for MavOdidHorAcc {
1083 fn default() -> Self {
1084 Self::DEFAULT
1085 }
1086}
1087#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1088#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1089#[cfg_attr(feature = "serde", serde(tag = "type"))]
1090#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1091#[repr(u32)]
1092#[doc = "These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65."]
1093pub enum FirmwareVersionType {
1094 #[doc = "development release"]
1095 FIRMWARE_VERSION_TYPE_DEV = 0,
1096 #[doc = "alpha release"]
1097 FIRMWARE_VERSION_TYPE_ALPHA = 64,
1098 #[doc = "beta release"]
1099 FIRMWARE_VERSION_TYPE_BETA = 128,
1100 #[doc = "release candidate"]
1101 FIRMWARE_VERSION_TYPE_RC = 192,
1102 #[doc = "official stable release"]
1103 FIRMWARE_VERSION_TYPE_OFFICIAL = 255,
1104}
1105impl FirmwareVersionType {
1106 pub const DEFAULT: Self = Self::FIRMWARE_VERSION_TYPE_DEV;
1107}
1108impl Default for FirmwareVersionType {
1109 fn default() -> Self {
1110 Self::DEFAULT
1111 }
1112}
1113#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1114#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1115#[cfg_attr(feature = "serde", serde(tag = "type"))]
1116#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1117#[repr(u32)]
1118#[doc = "Type of mission items being requested/sent in mission protocol."]
1119pub enum MavMissionType {
1120 #[doc = "Items are mission commands for main mission."]
1121 MAV_MISSION_TYPE_MISSION = 0,
1122 #[doc = "Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items."]
1123 MAV_MISSION_TYPE_FENCE = 1,
1124 #[doc = "Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items."]
1125 MAV_MISSION_TYPE_RALLY = 2,
1126 #[doc = "Only used in MISSION_CLEAR_ALL to clear all mission types."]
1127 MAV_MISSION_TYPE_ALL = 255,
1128}
1129impl MavMissionType {
1130 pub const DEFAULT: Self = Self::MAV_MISSION_TYPE_MISSION;
1131}
1132impl Default for MavMissionType {
1133 fn default() -> Self {
1134 Self::DEFAULT
1135 }
1136}
1137#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1138#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1139#[cfg_attr(feature = "serde", serde(tag = "type"))]
1140#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1141#[repr(u32)]
1142#[doc = "Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded."]
1143pub enum MavComponent {
1144 #[doc = "Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message."]
1145 MAV_COMP_ID_ALL = 0,
1146 #[doc = "System flight controller component (\"autopilot\"). Only one autopilot is expected in a particular system."]
1147 MAV_COMP_ID_AUTOPILOT1 = 1,
1148 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1149 MAV_COMP_ID_USER1 = 25,
1150 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1151 MAV_COMP_ID_USER2 = 26,
1152 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1153 MAV_COMP_ID_USER3 = 27,
1154 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1155 MAV_COMP_ID_USER4 = 28,
1156 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1157 MAV_COMP_ID_USER5 = 29,
1158 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1159 MAV_COMP_ID_USER6 = 30,
1160 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1161 MAV_COMP_ID_USER7 = 31,
1162 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1163 MAV_COMP_ID_USER8 = 32,
1164 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1165 MAV_COMP_ID_USER9 = 33,
1166 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1167 MAV_COMP_ID_USER10 = 34,
1168 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1169 MAV_COMP_ID_USER11 = 35,
1170 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1171 MAV_COMP_ID_USER12 = 36,
1172 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1173 MAV_COMP_ID_USER13 = 37,
1174 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1175 MAV_COMP_ID_USER14 = 38,
1176 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1177 MAV_COMP_ID_USER15 = 39,
1178 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1179 MAV_COMP_ID_USER16 = 40,
1180 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1181 MAV_COMP_ID_USER17 = 41,
1182 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1183 MAV_COMP_ID_USER18 = 42,
1184 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1185 MAV_COMP_ID_USER19 = 43,
1186 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1187 MAV_COMP_ID_USER20 = 44,
1188 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1189 MAV_COMP_ID_USER21 = 45,
1190 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1191 MAV_COMP_ID_USER22 = 46,
1192 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1193 MAV_COMP_ID_USER23 = 47,
1194 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1195 MAV_COMP_ID_USER24 = 48,
1196 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1197 MAV_COMP_ID_USER25 = 49,
1198 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1199 MAV_COMP_ID_USER26 = 50,
1200 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1201 MAV_COMP_ID_USER27 = 51,
1202 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1203 MAV_COMP_ID_USER28 = 52,
1204 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1205 MAV_COMP_ID_USER29 = 53,
1206 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1207 MAV_COMP_ID_USER30 = 54,
1208 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1209 MAV_COMP_ID_USER31 = 55,
1210 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1211 MAV_COMP_ID_USER32 = 56,
1212 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1213 MAV_COMP_ID_USER33 = 57,
1214 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1215 MAV_COMP_ID_USER34 = 58,
1216 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1217 MAV_COMP_ID_USER35 = 59,
1218 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1219 MAV_COMP_ID_USER36 = 60,
1220 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1221 MAV_COMP_ID_USER37 = 61,
1222 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1223 MAV_COMP_ID_USER38 = 62,
1224 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1225 MAV_COMP_ID_USER39 = 63,
1226 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1227 MAV_COMP_ID_USER40 = 64,
1228 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1229 MAV_COMP_ID_USER41 = 65,
1230 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1231 MAV_COMP_ID_USER42 = 66,
1232 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1233 MAV_COMP_ID_USER43 = 67,
1234 #[doc = "Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages)."]
1235 MAV_COMP_ID_TELEMETRY_RADIO = 68,
1236 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1237 MAV_COMP_ID_USER45 = 69,
1238 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1239 MAV_COMP_ID_USER46 = 70,
1240 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1241 MAV_COMP_ID_USER47 = 71,
1242 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1243 MAV_COMP_ID_USER48 = 72,
1244 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1245 MAV_COMP_ID_USER49 = 73,
1246 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1247 MAV_COMP_ID_USER50 = 74,
1248 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1249 MAV_COMP_ID_USER51 = 75,
1250 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1251 MAV_COMP_ID_USER52 = 76,
1252 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1253 MAV_COMP_ID_USER53 = 77,
1254 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1255 MAV_COMP_ID_USER54 = 78,
1256 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1257 MAV_COMP_ID_USER55 = 79,
1258 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1259 MAV_COMP_ID_USER56 = 80,
1260 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1261 MAV_COMP_ID_USER57 = 81,
1262 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1263 MAV_COMP_ID_USER58 = 82,
1264 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1265 MAV_COMP_ID_USER59 = 83,
1266 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1267 MAV_COMP_ID_USER60 = 84,
1268 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1269 MAV_COMP_ID_USER61 = 85,
1270 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1271 MAV_COMP_ID_USER62 = 86,
1272 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1273 MAV_COMP_ID_USER63 = 87,
1274 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1275 MAV_COMP_ID_USER64 = 88,
1276 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1277 MAV_COMP_ID_USER65 = 89,
1278 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1279 MAV_COMP_ID_USER66 = 90,
1280 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1281 MAV_COMP_ID_USER67 = 91,
1282 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1283 MAV_COMP_ID_USER68 = 92,
1284 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1285 MAV_COMP_ID_USER69 = 93,
1286 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1287 MAV_COMP_ID_USER70 = 94,
1288 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1289 MAV_COMP_ID_USER71 = 95,
1290 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1291 MAV_COMP_ID_USER72 = 96,
1292 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1293 MAV_COMP_ID_USER73 = 97,
1294 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1295 MAV_COMP_ID_USER74 = 98,
1296 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
1297 MAV_COMP_ID_USER75 = 99,
1298 #[doc = "Camera #1."]
1299 MAV_COMP_ID_CAMERA = 100,
1300 #[doc = "Camera #2."]
1301 MAV_COMP_ID_CAMERA2 = 101,
1302 #[doc = "Camera #3."]
1303 MAV_COMP_ID_CAMERA3 = 102,
1304 #[doc = "Camera #4."]
1305 MAV_COMP_ID_CAMERA4 = 103,
1306 #[doc = "Camera #5."]
1307 MAV_COMP_ID_CAMERA5 = 104,
1308 #[doc = "Camera #6."]
1309 MAV_COMP_ID_CAMERA6 = 105,
1310 #[doc = "Servo #1."]
1311 MAV_COMP_ID_SERVO1 = 140,
1312 #[doc = "Servo #2."]
1313 MAV_COMP_ID_SERVO2 = 141,
1314 #[doc = "Servo #3."]
1315 MAV_COMP_ID_SERVO3 = 142,
1316 #[doc = "Servo #4."]
1317 MAV_COMP_ID_SERVO4 = 143,
1318 #[doc = "Servo #5."]
1319 MAV_COMP_ID_SERVO5 = 144,
1320 #[doc = "Servo #6."]
1321 MAV_COMP_ID_SERVO6 = 145,
1322 #[doc = "Servo #7."]
1323 MAV_COMP_ID_SERVO7 = 146,
1324 #[doc = "Servo #8."]
1325 MAV_COMP_ID_SERVO8 = 147,
1326 #[doc = "Servo #9."]
1327 MAV_COMP_ID_SERVO9 = 148,
1328 #[doc = "Servo #10."]
1329 MAV_COMP_ID_SERVO10 = 149,
1330 #[doc = "Servo #11."]
1331 MAV_COMP_ID_SERVO11 = 150,
1332 #[doc = "Servo #12."]
1333 MAV_COMP_ID_SERVO12 = 151,
1334 #[doc = "Servo #13."]
1335 MAV_COMP_ID_SERVO13 = 152,
1336 #[doc = "Servo #14."]
1337 MAV_COMP_ID_SERVO14 = 153,
1338 #[doc = "Gimbal #1."]
1339 MAV_COMP_ID_GIMBAL = 154,
1340 #[doc = "Logging component."]
1341 MAV_COMP_ID_LOG = 155,
1342 #[doc = "Automatic Dependent Surveillance-Broadcast (ADS-B) component."]
1343 MAV_COMP_ID_ADSB = 156,
1344 #[doc = "On Screen Display (OSD) devices for video links."]
1345 MAV_COMP_ID_OSD = 157,
1346 #[doc = "Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice."]
1347 MAV_COMP_ID_PERIPHERAL = 158,
1348 #[doc = "Gimbal ID for QX1."]
1349 MAV_COMP_ID_QX1_GIMBAL = 159,
1350 #[doc = "FLARM collision alert component."]
1351 MAV_COMP_ID_FLARM = 160,
1352 #[doc = "Parachute component."]
1353 MAV_COMP_ID_PARACHUTE = 161,
1354 #[doc = "Winch component."]
1355 MAV_COMP_ID_WINCH = 169,
1356 #[doc = "Gimbal #2."]
1357 MAV_COMP_ID_GIMBAL2 = 171,
1358 #[doc = "Gimbal #3."]
1359 MAV_COMP_ID_GIMBAL3 = 172,
1360 #[doc = "Gimbal #4"]
1361 MAV_COMP_ID_GIMBAL4 = 173,
1362 #[doc = "Gimbal #5."]
1363 MAV_COMP_ID_GIMBAL5 = 174,
1364 #[doc = "Gimbal #6."]
1365 MAV_COMP_ID_GIMBAL6 = 175,
1366 #[doc = "Battery #1."]
1367 MAV_COMP_ID_BATTERY = 180,
1368 #[doc = "Battery #2."]
1369 MAV_COMP_ID_BATTERY2 = 181,
1370 #[doc = "CAN over MAVLink client."]
1371 MAV_COMP_ID_MAVCAN = 189,
1372 #[doc = "Component that can generate/supply a mission flight plan (e.g. GCS or developer API)."]
1373 MAV_COMP_ID_MISSIONPLANNER = 190,
1374 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1375 MAV_COMP_ID_ONBOARD_COMPUTER = 191,
1376 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1377 MAV_COMP_ID_ONBOARD_COMPUTER2 = 192,
1378 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1379 MAV_COMP_ID_ONBOARD_COMPUTER3 = 193,
1380 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
1381 MAV_COMP_ID_ONBOARD_COMPUTER4 = 194,
1382 #[doc = "Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.)."]
1383 MAV_COMP_ID_PATHPLANNER = 195,
1384 #[doc = "Component that plans a collision free path between two points."]
1385 MAV_COMP_ID_OBSTACLE_AVOIDANCE = 196,
1386 #[doc = "Component that provides position estimates using VIO techniques."]
1387 MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY = 197,
1388 #[doc = "Component that manages pairing of vehicle and GCS."]
1389 MAV_COMP_ID_PAIRING_MANAGER = 198,
1390 #[doc = "Inertial Measurement Unit (IMU) #1."]
1391 MAV_COMP_ID_IMU = 200,
1392 #[doc = "Inertial Measurement Unit (IMU) #2."]
1393 MAV_COMP_ID_IMU_2 = 201,
1394 #[doc = "Inertial Measurement Unit (IMU) #3."]
1395 MAV_COMP_ID_IMU_3 = 202,
1396 #[doc = "GPS #1."]
1397 MAV_COMP_ID_GPS = 220,
1398 #[doc = "GPS #2."]
1399 MAV_COMP_ID_GPS2 = 221,
1400 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
1401 MAV_COMP_ID_ODID_TXRX_1 = 236,
1402 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
1403 MAV_COMP_ID_ODID_TXRX_2 = 237,
1404 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
1405 MAV_COMP_ID_ODID_TXRX_3 = 238,
1406 #[doc = "Component to bridge MAVLink to UDP (i.e. from a UART)."]
1407 MAV_COMP_ID_UDP_BRIDGE = 240,
1408 #[doc = "Component to bridge to UART (i.e. from UDP)."]
1409 MAV_COMP_ID_UART_BRIDGE = 241,
1410 #[doc = "Component handling TUNNEL messages (e.g. vendor specific GUI of a component)."]
1411 MAV_COMP_ID_TUNNEL_NODE = 242,
1412 #[doc = "Illuminator"]
1413 MAV_COMP_ID_ILLUMINATOR = 243,
1414 #[doc = "Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.)."]
1415 MAV_COMP_ID_SYSTEM_CONTROL = 250,
1416}
1417impl MavComponent {
1418 pub const DEFAULT: Self = Self::MAV_COMP_ID_ALL;
1419}
1420impl Default for MavComponent {
1421 fn default() -> Self {
1422 Self::DEFAULT
1423 }
1424}
1425#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1426#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1427#[cfg_attr(feature = "serde", serde(tag = "type"))]
1428#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1429#[repr(u32)]
1430#[doc = "Type of GPS fix"]
1431pub enum GpsFixType {
1432 #[doc = "No GPS connected"]
1433 GPS_FIX_TYPE_NO_GPS = 0,
1434 #[doc = "No position information, GPS is connected"]
1435 GPS_FIX_TYPE_NO_FIX = 1,
1436 #[doc = "2D position"]
1437 GPS_FIX_TYPE_2D_FIX = 2,
1438 #[doc = "3D position"]
1439 GPS_FIX_TYPE_3D_FIX = 3,
1440 #[doc = "DGPS/SBAS aided 3D position"]
1441 GPS_FIX_TYPE_DGPS = 4,
1442 #[doc = "RTK float, 3D position"]
1443 GPS_FIX_TYPE_RTK_FLOAT = 5,
1444 #[doc = "RTK Fixed, 3D position"]
1445 GPS_FIX_TYPE_RTK_FIXED = 6,
1446 #[doc = "Static fixed, typically used for base stations"]
1447 GPS_FIX_TYPE_STATIC = 7,
1448 #[doc = "PPP, 3D position."]
1449 GPS_FIX_TYPE_PPP = 8,
1450}
1451impl GpsFixType {
1452 pub const DEFAULT: Self = Self::GPS_FIX_TYPE_NO_GPS;
1453}
1454impl Default for GpsFixType {
1455 fn default() -> Self {
1456 Self::DEFAULT
1457 }
1458}
1459#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1460#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1461#[cfg_attr(feature = "serde", serde(tag = "type"))]
1462#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1463#[repr(u32)]
1464#[doc = "Navigational status of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
1465pub enum AisNavStatus {
1466 #[doc = "Under way using engine."]
1467 UNDER_WAY = 0,
1468 AIS_NAV_ANCHORED = 1,
1469 AIS_NAV_UN_COMMANDED = 2,
1470 AIS_NAV_RESTRICTED_MANOEUVERABILITY = 3,
1471 AIS_NAV_DRAUGHT_CONSTRAINED = 4,
1472 AIS_NAV_MOORED = 5,
1473 AIS_NAV_AGROUND = 6,
1474 AIS_NAV_FISHING = 7,
1475 AIS_NAV_SAILING = 8,
1476 AIS_NAV_RESERVED_HSC = 9,
1477 AIS_NAV_RESERVED_WIG = 10,
1478 AIS_NAV_RESERVED_1 = 11,
1479 AIS_NAV_RESERVED_2 = 12,
1480 AIS_NAV_RESERVED_3 = 13,
1481 #[doc = "Search And Rescue Transponder."]
1482 AIS_NAV_AIS_SART = 14,
1483 #[doc = "Not available (default)."]
1484 AIS_NAV_UNKNOWN = 15,
1485}
1486impl AisNavStatus {
1487 pub const DEFAULT: Self = Self::UNDER_WAY;
1488}
1489impl Default for AisNavStatus {
1490 fn default() -> Self {
1491 Self::DEFAULT
1492 }
1493}
1494#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1495#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1496#[cfg_attr(feature = "serde", serde(tag = "type"))]
1497#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1498#[repr(u32)]
1499#[doc = "These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override."]
1500pub enum MavMode {
1501 #[doc = "System is not ready to fly, booting, calibrating, etc. No flag is set."]
1502 MAV_MODE_PREFLIGHT = 0,
1503 #[doc = "System is allowed to be active, under assisted RC control."]
1504 MAV_MODE_STABILIZE_DISARMED = 80,
1505 #[doc = "System is allowed to be active, under assisted RC control."]
1506 MAV_MODE_STABILIZE_ARMED = 208,
1507 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
1508 MAV_MODE_MANUAL_DISARMED = 64,
1509 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
1510 MAV_MODE_MANUAL_ARMED = 192,
1511 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
1512 MAV_MODE_GUIDED_DISARMED = 88,
1513 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
1514 MAV_MODE_GUIDED_ARMED = 216,
1515 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
1516 MAV_MODE_AUTO_DISARMED = 92,
1517 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
1518 MAV_MODE_AUTO_ARMED = 220,
1519 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
1520 MAV_MODE_TEST_DISARMED = 66,
1521 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
1522 MAV_MODE_TEST_ARMED = 194,
1523}
1524impl MavMode {
1525 pub const DEFAULT: Self = Self::MAV_MODE_PREFLIGHT;
1526}
1527impl Default for MavMode {
1528 fn default() -> Self {
1529 Self::DEFAULT
1530 }
1531}
1532bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags used in HIL_ACTUATOR_CONTROLS message."] pub struct HilActuatorControlsFlags : u64 { # [doc = "Simulation is using lockstep"] const HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP = 1 ; } }
1533impl HilActuatorControlsFlags {
1534 pub const DEFAULT: Self = Self::HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP;
1535}
1536impl Default for HilActuatorControlsFlags {
1537 fn default() -> Self {
1538 Self::DEFAULT
1539 }
1540}
1541#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1542#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1543#[cfg_attr(feature = "serde", serde(tag = "type"))]
1544#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1545#[repr(u32)]
1546#[doc = "Flags for CURRENT_EVENT_SEQUENCE."]
1547pub enum MavEventCurrentSequenceFlags {
1548 #[doc = "A sequence reset has happened (e.g. vehicle reboot)."]
1549 MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET = 1,
1550}
1551impl MavEventCurrentSequenceFlags {
1552 pub const DEFAULT: Self = Self::MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET;
1553}
1554impl Default for MavEventCurrentSequenceFlags {
1555 fn default() -> Self {
1556 Self::DEFAULT
1557 }
1558}
1559#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1560#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1561#[cfg_attr(feature = "serde", serde(tag = "type"))]
1562#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1563#[repr(u32)]
1564#[doc = "WiFi Mode."]
1565pub enum WifiConfigApMode {
1566 #[doc = "WiFi mode is undefined."]
1567 WIFI_CONFIG_AP_MODE_UNDEFINED = 0,
1568 #[doc = "WiFi configured as an access point."]
1569 WIFI_CONFIG_AP_MODE_AP = 1,
1570 #[doc = "WiFi configured as a station connected to an existing local WiFi network."]
1571 WIFI_CONFIG_AP_MODE_STATION = 2,
1572 #[doc = "WiFi disabled."]
1573 WIFI_CONFIG_AP_MODE_DISABLED = 3,
1574}
1575impl WifiConfigApMode {
1576 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_MODE_UNDEFINED;
1577}
1578impl Default for WifiConfigApMode {
1579 fn default() -> Self {
1580 Self::DEFAULT
1581 }
1582}
1583#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1584#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1585#[cfg_attr(feature = "serde", serde(tag = "type"))]
1586#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1587#[repr(u32)]
1588pub enum MavState {
1589 #[doc = "Uninitialized system, state is unknown."]
1590 MAV_STATE_UNINIT = 0,
1591 #[doc = "System is booting up."]
1592 MAV_STATE_BOOT = 1,
1593 #[doc = "System is calibrating and not flight-ready."]
1594 MAV_STATE_CALIBRATING = 2,
1595 #[doc = "System is grounded and on standby. It can be launched any time."]
1596 MAV_STATE_STANDBY = 3,
1597 #[doc = "System is active and might be already airborne. Motors are engaged."]
1598 MAV_STATE_ACTIVE = 4,
1599 #[doc = "System is in a non-normal flight mode (failsafe). It can however still navigate."]
1600 MAV_STATE_CRITICAL = 5,
1601 #[doc = "System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down."]
1602 MAV_STATE_EMERGENCY = 6,
1603 #[doc = "System just initialized its power-down sequence, will shut down now."]
1604 MAV_STATE_POWEROFF = 7,
1605 #[doc = "System is terminating itself (failsafe or commanded)."]
1606 MAV_STATE_FLIGHT_TERMINATION = 8,
1607}
1608impl MavState {
1609 pub const DEFAULT: Self = Self::MAV_STATE_UNINIT;
1610}
1611impl Default for MavState {
1612 fn default() -> Self {
1613 Self::DEFAULT
1614 }
1615}
1616#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1617#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1618#[cfg_attr(feature = "serde", serde(tag = "type"))]
1619#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1620#[repr(u32)]
1621#[doc = "Precision land modes (used in MAV_CMD_NAV_LAND)."]
1622pub enum PrecisionLandMode {
1623 #[doc = "Normal (non-precision) landing."]
1624 PRECISION_LAND_MODE_DISABLED = 0,
1625 #[doc = "Use precision landing if beacon detected when land command accepted, otherwise land normally."]
1626 PRECISION_LAND_MODE_OPPORTUNISTIC = 1,
1627 #[doc = "Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found)."]
1628 PRECISION_LAND_MODE_REQUIRED = 2,
1629}
1630impl PrecisionLandMode {
1631 pub const DEFAULT: Self = Self::PRECISION_LAND_MODE_DISABLED;
1632}
1633impl Default for PrecisionLandMode {
1634 fn default() -> Self {
1635 Self::DEFAULT
1636 }
1637}
1638bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report ESC failures."] pub struct EscFailureFlags : u16 { # [doc = "Over current failure."] const ESC_FAILURE_OVER_CURRENT = 1 ; # [doc = "Over voltage failure."] const ESC_FAILURE_OVER_VOLTAGE = 2 ; # [doc = "Over temperature failure."] const ESC_FAILURE_OVER_TEMPERATURE = 4 ; # [doc = "Over RPM failure."] const ESC_FAILURE_OVER_RPM = 8 ; # [doc = "Inconsistent command failure i.e. out of bounds."] const ESC_FAILURE_INCONSISTENT_CMD = 16 ; # [doc = "Motor stuck failure."] const ESC_FAILURE_MOTOR_STUCK = 32 ; # [doc = "Generic ESC failure."] const ESC_FAILURE_GENERIC = 64 ; } }
1639impl EscFailureFlags {
1640 pub const DEFAULT: Self = Self::ESC_FAILURE_OVER_CURRENT;
1641}
1642impl Default for EscFailureFlags {
1643 fn default() -> Self {
1644 Self::DEFAULT
1645 }
1646}
1647#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1648#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1649#[cfg_attr(feature = "serde", serde(tag = "type"))]
1650#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1651#[repr(u32)]
1652pub enum MavOdidDescType {
1653 #[doc = "Optional free-form text description of the purpose of the flight."]
1654 MAV_ODID_DESC_TYPE_TEXT = 0,
1655 #[doc = "Optional additional clarification when status == MAV_ODID_STATUS_EMERGENCY."]
1656 MAV_ODID_DESC_TYPE_EMERGENCY = 1,
1657 #[doc = "Optional additional clarification when status != MAV_ODID_STATUS_EMERGENCY."]
1658 MAV_ODID_DESC_TYPE_EXTENDED_STATUS = 2,
1659}
1660impl MavOdidDescType {
1661 pub const DEFAULT: Self = Self::MAV_ODID_DESC_TYPE_TEXT;
1662}
1663impl Default for MavOdidDescType {
1664 fn default() -> Self {
1665 Self::DEFAULT
1666 }
1667}
1668#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1669#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1670#[cfg_attr(feature = "serde", serde(tag = "type"))]
1671#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1672#[repr(u32)]
1673#[doc = "Possible responses from a CELLULAR_CONFIG message."]
1674pub enum CellularConfigResponse {
1675 #[doc = "Changes accepted."]
1676 CELLULAR_CONFIG_RESPONSE_ACCEPTED = 0,
1677 #[doc = "Invalid APN."]
1678 CELLULAR_CONFIG_RESPONSE_APN_ERROR = 1,
1679 #[doc = "Invalid PIN."]
1680 CELLULAR_CONFIG_RESPONSE_PIN_ERROR = 2,
1681 #[doc = "Changes rejected."]
1682 CELLULAR_CONFIG_RESPONSE_REJECTED = 3,
1683 #[doc = "PUK is required to unblock SIM card."]
1684 CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED = 4,
1685}
1686impl CellularConfigResponse {
1687 pub const DEFAULT: Self = Self::CELLULAR_CONFIG_RESPONSE_ACCEPTED;
1688}
1689impl Default for CellularConfigResponse {
1690 fn default() -> Self {
1691 Self::DEFAULT
1692 }
1693}
1694#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1695#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1696#[cfg_attr(feature = "serde", serde(tag = "type"))]
1697#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1698#[repr(u32)]
1699#[doc = "Actions being taken to mitigate/prevent fence breach"]
1700pub enum FenceMitigate {
1701 #[doc = "Unknown"]
1702 FENCE_MITIGATE_UNKNOWN = 0,
1703 #[doc = "No actions being taken"]
1704 FENCE_MITIGATE_NONE = 1,
1705 #[doc = "Velocity limiting active to prevent breach"]
1706 FENCE_MITIGATE_VEL_LIMIT = 2,
1707}
1708impl FenceMitigate {
1709 pub const DEFAULT: Self = Self::FENCE_MITIGATE_UNKNOWN;
1710}
1711impl Default for FenceMitigate {
1712 fn default() -> Self {
1713 Self::DEFAULT
1714 }
1715}
1716#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1717#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1718#[cfg_attr(feature = "serde", serde(tag = "type"))]
1719#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1720#[repr(u32)]
1721#[doc = "MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA)."]
1722pub enum MavType {
1723 #[doc = "Generic micro air vehicle"]
1724 MAV_TYPE_GENERIC = 0,
1725 #[doc = "Fixed wing aircraft."]
1726 MAV_TYPE_FIXED_WING = 1,
1727 #[doc = "Quadrotor"]
1728 MAV_TYPE_QUADROTOR = 2,
1729 #[doc = "Coaxial helicopter"]
1730 MAV_TYPE_COAXIAL = 3,
1731 #[doc = "Normal helicopter with tail rotor."]
1732 MAV_TYPE_HELICOPTER = 4,
1733 #[doc = "Ground installation"]
1734 MAV_TYPE_ANTENNA_TRACKER = 5,
1735 #[doc = "Operator control unit / ground control station"]
1736 MAV_TYPE_GCS = 6,
1737 #[doc = "Airship, controlled"]
1738 MAV_TYPE_AIRSHIP = 7,
1739 #[doc = "Free balloon, uncontrolled"]
1740 MAV_TYPE_FREE_BALLOON = 8,
1741 #[doc = "Rocket"]
1742 MAV_TYPE_ROCKET = 9,
1743 #[doc = "Ground rover"]
1744 MAV_TYPE_GROUND_ROVER = 10,
1745 #[doc = "Surface vessel, boat, ship"]
1746 MAV_TYPE_SURFACE_BOAT = 11,
1747 #[doc = "Submarine"]
1748 MAV_TYPE_SUBMARINE = 12,
1749 #[doc = "Hexarotor"]
1750 MAV_TYPE_HEXAROTOR = 13,
1751 #[doc = "Octorotor"]
1752 MAV_TYPE_OCTOROTOR = 14,
1753 #[doc = "Tricopter"]
1754 MAV_TYPE_TRICOPTER = 15,
1755 #[doc = "Flapping wing"]
1756 MAV_TYPE_FLAPPING_WING = 16,
1757 #[doc = "Kite"]
1758 MAV_TYPE_KITE = 17,
1759 #[doc = "Onboard companion controller"]
1760 MAV_TYPE_ONBOARD_CONTROLLER = 18,
1761 #[doc = "Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR."]
1762 MAV_TYPE_VTOL_TAILSITTER_DUOROTOR = 19,
1763 #[doc = "Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR."]
1764 MAV_TYPE_VTOL_TAILSITTER_QUADROTOR = 20,
1765 #[doc = "Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight."]
1766 MAV_TYPE_VTOL_TILTROTOR = 21,
1767 #[doc = "VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases."]
1768 MAV_TYPE_VTOL_FIXEDROTOR = 22,
1769 #[doc = "Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate."]
1770 MAV_TYPE_VTOL_TAILSITTER = 23,
1771 #[doc = "Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode."]
1772 MAV_TYPE_VTOL_TILTWING = 24,
1773 #[doc = "VTOL reserved 5"]
1774 MAV_TYPE_VTOL_RESERVED5 = 25,
1775 #[doc = "Gimbal"]
1776 MAV_TYPE_GIMBAL = 26,
1777 #[doc = "ADSB system"]
1778 MAV_TYPE_ADSB = 27,
1779 #[doc = "Steerable, nonrigid airfoil"]
1780 MAV_TYPE_PARAFOIL = 28,
1781 #[doc = "Dodecarotor"]
1782 MAV_TYPE_DODECAROTOR = 29,
1783 #[doc = "Camera"]
1784 MAV_TYPE_CAMERA = 30,
1785 #[doc = "Charging station"]
1786 MAV_TYPE_CHARGING_STATION = 31,
1787 #[doc = "FLARM collision avoidance system"]
1788 MAV_TYPE_FLARM = 32,
1789 #[doc = "Servo"]
1790 MAV_TYPE_SERVO = 33,
1791 #[doc = "Open Drone ID. See <https://mavlink.io/en/services/opendroneid.html>."]
1792 MAV_TYPE_ODID = 34,
1793 #[doc = "Decarotor"]
1794 MAV_TYPE_DECAROTOR = 35,
1795 #[doc = "Battery"]
1796 MAV_TYPE_BATTERY = 36,
1797 #[doc = "Parachute"]
1798 MAV_TYPE_PARACHUTE = 37,
1799 #[doc = "Log"]
1800 MAV_TYPE_LOG = 38,
1801 #[doc = "OSD"]
1802 MAV_TYPE_OSD = 39,
1803 #[doc = "IMU"]
1804 MAV_TYPE_IMU = 40,
1805 #[doc = "GPS"]
1806 MAV_TYPE_GPS = 41,
1807 #[doc = "Winch"]
1808 MAV_TYPE_WINCH = 42,
1809 #[doc = "Generic multirotor that does not fit into a specific type or whose type is unknown"]
1810 MAV_TYPE_GENERIC_MULTIROTOR = 43,
1811 #[doc = "Illuminator. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
1812 MAV_TYPE_ILLUMINATOR = 44,
1813 #[doc = "Orbiter spacecraft. Includes satellites orbiting terrestrial and extra-terrestrial bodies. Follows NASA Spacecraft Classification."]
1814 MAV_TYPE_SPACECRAFT_ORBITER = 45,
1815}
1816impl MavType {
1817 pub const DEFAULT: Self = Self::MAV_TYPE_GENERIC;
1818}
1819impl Default for MavType {
1820 fn default() -> Self {
1821 Self::DEFAULT
1822 }
1823}
1824#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1825#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1826#[cfg_attr(feature = "serde", serde(tag = "type"))]
1827#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1828#[repr(u32)]
1829#[doc = "Bitmap of options for the MAV_CMD_DO_REPOSITION"]
1830pub enum MavDoRepositionFlags {
1831 #[doc = "The aircraft should immediately transition into guided. This should not be set for follow me applications"]
1832 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE = 1,
1833}
1834impl MavDoRepositionFlags {
1835 pub const DEFAULT: Self = Self::MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
1836}
1837impl Default for MavDoRepositionFlags {
1838 fn default() -> Self {
1839 Self::DEFAULT
1840 }
1841}
1842#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1843#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1844#[cfg_attr(feature = "serde", serde(tag = "type"))]
1845#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1846#[repr(u32)]
1847#[doc = "Specifies the datatype of a MAVLink parameter."]
1848pub enum MavParamType {
1849 #[doc = "8-bit unsigned integer"]
1850 MAV_PARAM_TYPE_UINT8 = 1,
1851 #[doc = "8-bit signed integer"]
1852 MAV_PARAM_TYPE_INT8 = 2,
1853 #[doc = "16-bit unsigned integer"]
1854 MAV_PARAM_TYPE_UINT16 = 3,
1855 #[doc = "16-bit signed integer"]
1856 MAV_PARAM_TYPE_INT16 = 4,
1857 #[doc = "32-bit unsigned integer"]
1858 MAV_PARAM_TYPE_UINT32 = 5,
1859 #[doc = "32-bit signed integer"]
1860 MAV_PARAM_TYPE_INT32 = 6,
1861 #[doc = "64-bit unsigned integer"]
1862 MAV_PARAM_TYPE_UINT64 = 7,
1863 #[doc = "64-bit signed integer"]
1864 MAV_PARAM_TYPE_INT64 = 8,
1865 #[doc = "32-bit floating-point"]
1866 MAV_PARAM_TYPE_REAL32 = 9,
1867 #[doc = "64-bit floating-point"]
1868 MAV_PARAM_TYPE_REAL64 = 10,
1869}
1870impl MavParamType {
1871 pub const DEFAULT: Self = Self::MAV_PARAM_TYPE_UINT8;
1872}
1873impl Default for MavParamType {
1874 fn default() -> Self {
1875 Self::DEFAULT
1876 }
1877}
1878#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1879#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1880#[cfg_attr(feature = "serde", serde(tag = "type"))]
1881#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1882#[repr(u32)]
1883#[doc = "SERIAL_CONTROL device types"]
1884pub enum SerialControlDev {
1885 #[doc = "First telemetry port"]
1886 SERIAL_CONTROL_DEV_TELEM1 = 0,
1887 #[doc = "Second telemetry port"]
1888 SERIAL_CONTROL_DEV_TELEM2 = 1,
1889 #[doc = "First GPS port"]
1890 SERIAL_CONTROL_DEV_GPS1 = 2,
1891 #[doc = "Second GPS port"]
1892 SERIAL_CONTROL_DEV_GPS2 = 3,
1893 #[doc = "system shell"]
1894 SERIAL_CONTROL_DEV_SHELL = 10,
1895 #[doc = "SERIAL0"]
1896 SERIAL_CONTROL_SERIAL0 = 100,
1897 #[doc = "SERIAL1"]
1898 SERIAL_CONTROL_SERIAL1 = 101,
1899 #[doc = "SERIAL2"]
1900 SERIAL_CONTROL_SERIAL2 = 102,
1901 #[doc = "SERIAL3"]
1902 SERIAL_CONTROL_SERIAL3 = 103,
1903 #[doc = "SERIAL4"]
1904 SERIAL_CONTROL_SERIAL4 = 104,
1905 #[doc = "SERIAL5"]
1906 SERIAL_CONTROL_SERIAL5 = 105,
1907 #[doc = "SERIAL6"]
1908 SERIAL_CONTROL_SERIAL6 = 106,
1909 #[doc = "SERIAL7"]
1910 SERIAL_CONTROL_SERIAL7 = 107,
1911 #[doc = "SERIAL8"]
1912 SERIAL_CONTROL_SERIAL8 = 108,
1913 #[doc = "SERIAL9"]
1914 SERIAL_CONTROL_SERIAL9 = 109,
1915}
1916impl SerialControlDev {
1917 pub const DEFAULT: Self = Self::SERIAL_CONTROL_DEV_TELEM1;
1918}
1919impl Default for SerialControlDev {
1920 fn default() -> Self {
1921 Self::DEFAULT
1922 }
1923}
1924#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1925#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1926#[cfg_attr(feature = "serde", serde(tag = "type"))]
1927#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1928#[repr(u32)]
1929#[doc = "Indicates the ESC connection type."]
1930pub enum EscConnectionType {
1931 #[doc = "Traditional PPM ESC."]
1932 ESC_CONNECTION_TYPE_PPM = 0,
1933 #[doc = "Serial Bus connected ESC."]
1934 ESC_CONNECTION_TYPE_SERIAL = 1,
1935 #[doc = "One Shot PPM ESC."]
1936 ESC_CONNECTION_TYPE_ONESHOT = 2,
1937 #[doc = "I2C ESC."]
1938 ESC_CONNECTION_TYPE_I2C = 3,
1939 #[doc = "CAN-Bus ESC."]
1940 ESC_CONNECTION_TYPE_CAN = 4,
1941 #[doc = "DShot ESC."]
1942 ESC_CONNECTION_TYPE_DSHOT = 5,
1943}
1944impl EscConnectionType {
1945 pub const DEFAULT: Self = Self::ESC_CONNECTION_TYPE_PPM;
1946}
1947impl Default for EscConnectionType {
1948 fn default() -> Self {
1949 Self::DEFAULT
1950 }
1951}
1952#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1953#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1954#[cfg_attr(feature = "serde", serde(tag = "type"))]
1955#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1956#[repr(u32)]
1957#[doc = "Enumeration of battery types"]
1958pub enum MavBatteryType {
1959 #[doc = "Not specified."]
1960 MAV_BATTERY_TYPE_UNKNOWN = 0,
1961 #[doc = "Lithium polymer battery"]
1962 MAV_BATTERY_TYPE_LIPO = 1,
1963 #[doc = "Lithium-iron-phosphate battery"]
1964 MAV_BATTERY_TYPE_LIFE = 2,
1965 #[doc = "Lithium-ION battery"]
1966 MAV_BATTERY_TYPE_LION = 3,
1967 #[doc = "Nickel metal hydride battery"]
1968 MAV_BATTERY_TYPE_NIMH = 4,
1969}
1970impl MavBatteryType {
1971 pub const DEFAULT: Self = Self::MAV_BATTERY_TYPE_UNKNOWN;
1972}
1973impl Default for MavBatteryType {
1974 fn default() -> Self {
1975 Self::DEFAULT
1976 }
1977}
1978#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1979#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1980#[cfg_attr(feature = "serde", serde(tag = "type"))]
1981#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1982#[repr(u32)]
1983#[doc = "Enumeration of the ADSB altimeter types"]
1984pub enum AdsbAltitudeType {
1985 #[doc = "Altitude reported from a Baro source using QNH reference"]
1986 ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0,
1987 #[doc = "Altitude reported from a GNSS source"]
1988 ADSB_ALTITUDE_TYPE_GEOMETRIC = 1,
1989}
1990impl AdsbAltitudeType {
1991 pub const DEFAULT: Self = Self::ADSB_ALTITUDE_TYPE_PRESSURE_QNH;
1992}
1993impl Default for AdsbAltitudeType {
1994 fn default() -> Self {
1995 Self::DEFAULT
1996 }
1997}
1998#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1999#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2000#[cfg_attr(feature = "serde", serde(tag = "type"))]
2001#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2002#[repr(u32)]
2003#[doc = "Zoom types for MAV_CMD_SET_CAMERA_ZOOM"]
2004pub enum CameraZoomType {
2005 #[doc = "Zoom one step increment (-1 for wide, 1 for tele)"]
2006 ZOOM_TYPE_STEP = 0,
2007 #[doc = "Continuous normalized zoom in/out rate until stopped. Range -1..1, negative: wide, positive: narrow/tele, 0 to stop zooming. Other values should be clipped to the range."]
2008 ZOOM_TYPE_CONTINUOUS = 1,
2009 #[doc = "Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0)"]
2010 ZOOM_TYPE_RANGE = 2,
2011 #[doc = "Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)"]
2012 ZOOM_TYPE_FOCAL_LENGTH = 3,
2013 #[doc = "Zoom value as horizontal field of view in degrees."]
2014 ZOOM_TYPE_HORIZONTAL_FOV = 4,
2015}
2016impl CameraZoomType {
2017 pub const DEFAULT: Self = Self::ZOOM_TYPE_STEP;
2018}
2019impl Default for CameraZoomType {
2020 fn default() -> Self {
2021 Self::DEFAULT
2022 }
2023}
2024#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2025#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2026#[cfg_attr(feature = "serde", serde(tag = "type"))]
2027#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2028#[repr(u32)]
2029#[doc = "Actuator output function. Values greater or equal to 1000 are autopilot-specific."]
2030pub enum ActuatorOutputFunction {
2031 #[doc = "No function (disabled)."]
2032 ACTUATOR_OUTPUT_FUNCTION_NONE = 0,
2033 #[doc = "Motor 1"]
2034 ACTUATOR_OUTPUT_FUNCTION_MOTOR1 = 1,
2035 #[doc = "Motor 2"]
2036 ACTUATOR_OUTPUT_FUNCTION_MOTOR2 = 2,
2037 #[doc = "Motor 3"]
2038 ACTUATOR_OUTPUT_FUNCTION_MOTOR3 = 3,
2039 #[doc = "Motor 4"]
2040 ACTUATOR_OUTPUT_FUNCTION_MOTOR4 = 4,
2041 #[doc = "Motor 5"]
2042 ACTUATOR_OUTPUT_FUNCTION_MOTOR5 = 5,
2043 #[doc = "Motor 6"]
2044 ACTUATOR_OUTPUT_FUNCTION_MOTOR6 = 6,
2045 #[doc = "Motor 7"]
2046 ACTUATOR_OUTPUT_FUNCTION_MOTOR7 = 7,
2047 #[doc = "Motor 8"]
2048 ACTUATOR_OUTPUT_FUNCTION_MOTOR8 = 8,
2049 #[doc = "Motor 9"]
2050 ACTUATOR_OUTPUT_FUNCTION_MOTOR9 = 9,
2051 #[doc = "Motor 10"]
2052 ACTUATOR_OUTPUT_FUNCTION_MOTOR10 = 10,
2053 #[doc = "Motor 11"]
2054 ACTUATOR_OUTPUT_FUNCTION_MOTOR11 = 11,
2055 #[doc = "Motor 12"]
2056 ACTUATOR_OUTPUT_FUNCTION_MOTOR12 = 12,
2057 #[doc = "Motor 13"]
2058 ACTUATOR_OUTPUT_FUNCTION_MOTOR13 = 13,
2059 #[doc = "Motor 14"]
2060 ACTUATOR_OUTPUT_FUNCTION_MOTOR14 = 14,
2061 #[doc = "Motor 15"]
2062 ACTUATOR_OUTPUT_FUNCTION_MOTOR15 = 15,
2063 #[doc = "Motor 16"]
2064 ACTUATOR_OUTPUT_FUNCTION_MOTOR16 = 16,
2065 #[doc = "Servo 1"]
2066 ACTUATOR_OUTPUT_FUNCTION_SERVO1 = 33,
2067 #[doc = "Servo 2"]
2068 ACTUATOR_OUTPUT_FUNCTION_SERVO2 = 34,
2069 #[doc = "Servo 3"]
2070 ACTUATOR_OUTPUT_FUNCTION_SERVO3 = 35,
2071 #[doc = "Servo 4"]
2072 ACTUATOR_OUTPUT_FUNCTION_SERVO4 = 36,
2073 #[doc = "Servo 5"]
2074 ACTUATOR_OUTPUT_FUNCTION_SERVO5 = 37,
2075 #[doc = "Servo 6"]
2076 ACTUATOR_OUTPUT_FUNCTION_SERVO6 = 38,
2077 #[doc = "Servo 7"]
2078 ACTUATOR_OUTPUT_FUNCTION_SERVO7 = 39,
2079 #[doc = "Servo 8"]
2080 ACTUATOR_OUTPUT_FUNCTION_SERVO8 = 40,
2081 #[doc = "Servo 9"]
2082 ACTUATOR_OUTPUT_FUNCTION_SERVO9 = 41,
2083 #[doc = "Servo 10"]
2084 ACTUATOR_OUTPUT_FUNCTION_SERVO10 = 42,
2085 #[doc = "Servo 11"]
2086 ACTUATOR_OUTPUT_FUNCTION_SERVO11 = 43,
2087 #[doc = "Servo 12"]
2088 ACTUATOR_OUTPUT_FUNCTION_SERVO12 = 44,
2089 #[doc = "Servo 13"]
2090 ACTUATOR_OUTPUT_FUNCTION_SERVO13 = 45,
2091 #[doc = "Servo 14"]
2092 ACTUATOR_OUTPUT_FUNCTION_SERVO14 = 46,
2093 #[doc = "Servo 15"]
2094 ACTUATOR_OUTPUT_FUNCTION_SERVO15 = 47,
2095 #[doc = "Servo 16"]
2096 ACTUATOR_OUTPUT_FUNCTION_SERVO16 = 48,
2097}
2098impl ActuatorOutputFunction {
2099 pub const DEFAULT: Self = Self::ACTUATOR_OUTPUT_FUNCTION_NONE;
2100}
2101impl Default for ActuatorOutputFunction {
2102 fn default() -> Self {
2103 Self::DEFAULT
2104 }
2105}
2106#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2107#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2108#[cfg_attr(feature = "serde", serde(tag = "type"))]
2109#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2110#[repr(u32)]
2111pub enum MavOdidUaType {
2112 #[doc = "No UA (Unmanned Aircraft) type defined."]
2113 MAV_ODID_UA_TYPE_NONE = 0,
2114 #[doc = "Aeroplane/Airplane. Fixed wing."]
2115 MAV_ODID_UA_TYPE_AEROPLANE = 1,
2116 #[doc = "Helicopter or multirotor."]
2117 MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR = 2,
2118 #[doc = "Gyroplane."]
2119 MAV_ODID_UA_TYPE_GYROPLANE = 3,
2120 #[doc = "VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically."]
2121 MAV_ODID_UA_TYPE_HYBRID_LIFT = 4,
2122 #[doc = "Ornithopter."]
2123 MAV_ODID_UA_TYPE_ORNITHOPTER = 5,
2124 #[doc = "Glider."]
2125 MAV_ODID_UA_TYPE_GLIDER = 6,
2126 #[doc = "Kite."]
2127 MAV_ODID_UA_TYPE_KITE = 7,
2128 #[doc = "Free Balloon."]
2129 MAV_ODID_UA_TYPE_FREE_BALLOON = 8,
2130 #[doc = "Captive Balloon."]
2131 MAV_ODID_UA_TYPE_CAPTIVE_BALLOON = 9,
2132 #[doc = "Airship. E.g. a blimp."]
2133 MAV_ODID_UA_TYPE_AIRSHIP = 10,
2134 #[doc = "Free Fall/Parachute (unpowered)."]
2135 MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE = 11,
2136 #[doc = "Rocket."]
2137 MAV_ODID_UA_TYPE_ROCKET = 12,
2138 #[doc = "Tethered powered aircraft."]
2139 MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT = 13,
2140 #[doc = "Ground Obstacle."]
2141 MAV_ODID_UA_TYPE_GROUND_OBSTACLE = 14,
2142 #[doc = "Other type of aircraft not listed earlier."]
2143 MAV_ODID_UA_TYPE_OTHER = 15,
2144}
2145impl MavOdidUaType {
2146 pub const DEFAULT: Self = Self::MAV_ODID_UA_TYPE_NONE;
2147}
2148impl Default for MavOdidUaType {
2149 fn default() -> Self {
2150 Self::DEFAULT
2151 }
2152}
2153#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2154#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2155#[cfg_attr(feature = "serde", serde(tag = "type"))]
2156#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2157#[repr(u32)]
2158#[doc = "Camera sources for MAV_CMD_SET_CAMERA_SOURCE"]
2159pub enum CameraSource {
2160 #[doc = "Default camera source."]
2161 CAMERA_SOURCE_DEFAULT = 0,
2162 #[doc = "RGB camera source."]
2163 CAMERA_SOURCE_RGB = 1,
2164 #[doc = "IR camera source."]
2165 CAMERA_SOURCE_IR = 2,
2166 #[doc = "NDVI camera source."]
2167 CAMERA_SOURCE_NDVI = 3,
2168}
2169impl CameraSource {
2170 pub const DEFAULT: Self = Self::CAMERA_SOURCE_DEFAULT;
2171}
2172impl Default for CameraSource {
2173 fn default() -> Self {
2174 Self::DEFAULT
2175 }
2176}
2177#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2178#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2179#[cfg_attr(feature = "serde", serde(tag = "type"))]
2180#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2181#[repr(u32)]
2182#[doc = "Enumeration of battery functions"]
2183pub enum MavBatteryFunction {
2184 #[doc = "Battery function is unknown"]
2185 MAV_BATTERY_FUNCTION_UNKNOWN = 0,
2186 #[doc = "Battery supports all flight systems"]
2187 MAV_BATTERY_FUNCTION_ALL = 1,
2188 #[doc = "Battery for the propulsion system"]
2189 MAV_BATTERY_FUNCTION_PROPULSION = 2,
2190 #[doc = "Avionics battery"]
2191 MAV_BATTERY_FUNCTION_AVIONICS = 3,
2192 #[doc = "Payload battery"]
2193 MAV_BATTERY_FUNCTION_PAYLOAD = 4,
2194}
2195impl MavBatteryFunction {
2196 pub const DEFAULT: Self = Self::MAV_BATTERY_FUNCTION_UNKNOWN;
2197}
2198impl Default for MavBatteryFunction {
2199 fn default() -> Self {
2200 Self::DEFAULT
2201 }
2202}
2203#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2204#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2205#[cfg_attr(feature = "serde", serde(tag = "type"))]
2206#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2207#[repr(u32)]
2208pub enum MavArmAuthDeniedReason {
2209 #[doc = "Not a specific reason"]
2210 MAV_ARM_AUTH_DENIED_REASON_GENERIC = 0,
2211 #[doc = "Authorizer will send the error as string to GCS"]
2212 MAV_ARM_AUTH_DENIED_REASON_NONE = 1,
2213 #[doc = "At least one waypoint have a invalid value"]
2214 MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2,
2215 #[doc = "Timeout in the authorizer process(in case it depends on network)"]
2216 MAV_ARM_AUTH_DENIED_REASON_TIMEOUT = 3,
2217 #[doc = "Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied."]
2218 MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4,
2219 #[doc = "Weather is not good to fly"]
2220 MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5,
2221}
2222impl MavArmAuthDeniedReason {
2223 pub const DEFAULT: Self = Self::MAV_ARM_AUTH_DENIED_REASON_GENERIC;
2224}
2225impl Default for MavArmAuthDeniedReason {
2226 fn default() -> Self {
2227 Self::DEFAULT
2228 }
2229}
2230#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2231#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2232#[cfg_attr(feature = "serde", serde(tag = "type"))]
2233#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2234#[repr(u32)]
2235pub enum MavOdidSpeedAcc {
2236 #[doc = "The speed accuracy is unknown."]
2237 MAV_ODID_SPEED_ACC_UNKNOWN = 0,
2238 #[doc = "The speed accuracy is smaller than 10 meters per second."]
2239 MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND = 1,
2240 #[doc = "The speed accuracy is smaller than 3 meters per second."]
2241 MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND = 2,
2242 #[doc = "The speed accuracy is smaller than 1 meters per second."]
2243 MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND = 3,
2244 #[doc = "The speed accuracy is smaller than 0.3 meters per second."]
2245 MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND = 4,
2246}
2247impl MavOdidSpeedAcc {
2248 pub const DEFAULT: Self = Self::MAV_ODID_SPEED_ACC_UNKNOWN;
2249}
2250impl Default for MavOdidSpeedAcc {
2251 fn default() -> Self {
2252 Self::DEFAULT
2253 }
2254}
2255#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2256#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2257#[cfg_attr(feature = "serde", serde(tag = "type"))]
2258#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2259#[repr(u32)]
2260pub enum MavOdidClassificationType {
2261 #[doc = "The classification type for the UA is undeclared."]
2262 MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED = 0,
2263 #[doc = "The classification type for the UA follows EU (European Union) specifications."]
2264 MAV_ODID_CLASSIFICATION_TYPE_EU = 1,
2265}
2266impl MavOdidClassificationType {
2267 pub const DEFAULT: Self = Self::MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED;
2268}
2269impl Default for MavOdidClassificationType {
2270 fn default() -> Self {
2271 Self::DEFAULT
2272 }
2273}
2274bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIL_SENSOR message indicate which fields have updated since the last message"] pub struct HilSensorUpdatedFlags : u32 { # [doc = "The value in the xacc field has been updated"] const HIL_SENSOR_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIL_SENSOR_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated"] const HIL_SENSOR_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIL_SENSOR_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIL_SENSOR_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIL_SENSOR_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIL_SENSOR_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIL_SENSOR_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIL_SENSOR_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIL_SENSOR_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIL_SENSOR_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIL_SENSOR_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIL_SENSOR_UPDATED_TEMPERATURE = 4096 ; # [doc = "Full reset of attitude/position/velocities/etc was performed in sim (Bit 31)."] const HIL_SENSOR_UPDATED_RESET = 2147483648 ; } }
2275impl HilSensorUpdatedFlags {
2276 pub const DEFAULT: Self = Self::HIL_SENSOR_UPDATED_XACC;
2277}
2278impl Default for HilSensorUpdatedFlags {
2279 fn default() -> Self {
2280 Self::DEFAULT
2281 }
2282}
2283#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2284#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2285#[cfg_attr(feature = "serde", serde(tag = "type"))]
2286#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2287#[repr(u32)]
2288#[doc = "Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST."]
2289pub enum MotorTestOrder {
2290 #[doc = "Default autopilot motor test method."]
2291 MOTOR_TEST_ORDER_DEFAULT = 0,
2292 #[doc = "Motor numbers are specified as their index in a predefined vehicle-specific sequence."]
2293 MOTOR_TEST_ORDER_SEQUENCE = 1,
2294 #[doc = "Motor numbers are specified as the output as labeled on the board."]
2295 MOTOR_TEST_ORDER_BOARD = 2,
2296}
2297impl MotorTestOrder {
2298 pub const DEFAULT: Self = Self::MOTOR_TEST_ORDER_DEFAULT;
2299}
2300impl Default for MotorTestOrder {
2301 fn default() -> Self {
2302 Self::DEFAULT
2303 }
2304}
2305bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIGHRES_IMU message indicate which fields have updated since the last message"] pub struct HighresImuUpdatedFlags : u16 { # [doc = "The value in the xacc field has been updated"] const HIGHRES_IMU_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIGHRES_IMU_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated since"] const HIGHRES_IMU_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIGHRES_IMU_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIGHRES_IMU_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIGHRES_IMU_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIGHRES_IMU_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIGHRES_IMU_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIGHRES_IMU_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIGHRES_IMU_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIGHRES_IMU_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIGHRES_IMU_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIGHRES_IMU_UPDATED_TEMPERATURE = 4096 ; } }
2306impl HighresImuUpdatedFlags {
2307 pub const DEFAULT: Self = Self::HIGHRES_IMU_UPDATED_XACC;
2308}
2309impl Default for HighresImuUpdatedFlags {
2310 fn default() -> Self {
2311 Self::DEFAULT
2312 }
2313}
2314#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2315#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2316#[cfg_attr(feature = "serde", serde(tag = "type"))]
2317#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2318#[repr(u32)]
2319#[doc = "MAV FTP error codes (<https://mavlink.io/en/services/ftp.html>)"]
2320pub enum MavFtpErr {
2321 #[doc = "None: No error"]
2322 MAV_FTP_ERR_NONE = 0,
2323 #[doc = "Fail: Unknown failure"]
2324 MAV_FTP_ERR_FAIL = 1,
2325 #[doc = "FailErrno: Command failed, Err number sent back in PayloadHeader.data[1]. \t\tThis is a file-system error number understood by the server operating system."]
2326 MAV_FTP_ERR_FAILERRNO = 2,
2327 #[doc = "InvalidDataSize: Payload size is invalid"]
2328 MAV_FTP_ERR_INVALIDDATASIZE = 3,
2329 #[doc = "InvalidSession: Session is not currently open"]
2330 MAV_FTP_ERR_INVALIDSESSION = 4,
2331 #[doc = "NoSessionsAvailable: All available sessions are already in use"]
2332 MAV_FTP_ERR_NOSESSIONSAVAILABLE = 5,
2333 #[doc = "EOF: Offset past end of file for ListDirectory and ReadFile commands"]
2334 MAV_FTP_ERR_EOF = 6,
2335 #[doc = "UnknownCommand: Unknown command / opcode"]
2336 MAV_FTP_ERR_UNKNOWNCOMMAND = 7,
2337 #[doc = "FileExists: File/directory already exists"]
2338 MAV_FTP_ERR_FILEEXISTS = 8,
2339 #[doc = "FileProtected: File/directory is write protected"]
2340 MAV_FTP_ERR_FILEPROTECTED = 9,
2341 #[doc = "FileNotFound: File/directory not found"]
2342 MAV_FTP_ERR_FILENOTFOUND = 10,
2343}
2344impl MavFtpErr {
2345 pub const DEFAULT: Self = Self::MAV_FTP_ERR_NONE;
2346}
2347impl Default for MavFtpErr {
2348 fn default() -> Self {
2349 Self::DEFAULT
2350 }
2351}
2352#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2353#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2354#[cfg_attr(feature = "serde", serde(tag = "type"))]
2355#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2356#[repr(u32)]
2357pub enum MavOdidHeightRef {
2358 #[doc = "The height field is relative to the take-off location."]
2359 MAV_ODID_HEIGHT_REF_OVER_TAKEOFF = 0,
2360 #[doc = "The height field is relative to ground."]
2361 MAV_ODID_HEIGHT_REF_OVER_GROUND = 1,
2362}
2363impl MavOdidHeightRef {
2364 pub const DEFAULT: Self = Self::MAV_ODID_HEIGHT_REF_OVER_TAKEOFF;
2365}
2366impl Default for MavOdidHeightRef {
2367 fn default() -> Self {
2368 Self::DEFAULT
2369 }
2370}
2371#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2372#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2373#[cfg_attr(feature = "serde", serde(tag = "type"))]
2374#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2375#[repr(u32)]
2376pub enum MagCalStatus {
2377 MAG_CAL_NOT_STARTED = 0,
2378 MAG_CAL_WAITING_TO_START = 1,
2379 MAG_CAL_RUNNING_STEP_ONE = 2,
2380 MAG_CAL_RUNNING_STEP_TWO = 3,
2381 MAG_CAL_SUCCESS = 4,
2382 MAG_CAL_FAILED = 5,
2383 MAG_CAL_BAD_ORIENTATION = 6,
2384 MAG_CAL_BAD_RADIUS = 7,
2385}
2386impl MagCalStatus {
2387 pub const DEFAULT: Self = Self::MAG_CAL_NOT_STARTED;
2388}
2389impl Default for MagCalStatus {
2390 fn default() -> Self {
2391 Self::DEFAULT
2392 }
2393}
2394#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2395#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2396#[cfg_attr(feature = "serde", serde(tag = "type"))]
2397#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2398#[repr(u32)]
2399#[doc = "Result from a MAVLink command (MAV_CMD)"]
2400pub enum MavResult {
2401 #[doc = "Command is valid (is supported and has valid parameters), and was executed."]
2402 MAV_RESULT_ACCEPTED = 0,
2403 #[doc = "Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work."]
2404 MAV_RESULT_TEMPORARILY_REJECTED = 1,
2405 #[doc = "Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work."]
2406 MAV_RESULT_DENIED = 2,
2407 #[doc = "Command is not supported (unknown)."]
2408 MAV_RESULT_UNSUPPORTED = 3,
2409 #[doc = "Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc."]
2410 MAV_RESULT_FAILED = 4,
2411 #[doc = "Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation."]
2412 MAV_RESULT_IN_PROGRESS = 5,
2413 #[doc = "Command has been cancelled (as a result of receiving a COMMAND_CANCEL message)."]
2414 MAV_RESULT_CANCELLED = 6,
2415 #[doc = "Command is only accepted when sent as a COMMAND_LONG."]
2416 MAV_RESULT_COMMAND_LONG_ONLY = 7,
2417 #[doc = "Command is only accepted when sent as a COMMAND_INT."]
2418 MAV_RESULT_COMMAND_INT_ONLY = 8,
2419 #[doc = "Command is invalid because a frame is required and the specified frame is not supported."]
2420 MAV_RESULT_COMMAND_UNSUPPORTED_MAV_FRAME = 9,
2421}
2422impl MavResult {
2423 pub const DEFAULT: Self = Self::MAV_RESULT_ACCEPTED;
2424}
2425impl Default for MavResult {
2426 fn default() -> Self {
2427 Self::DEFAULT
2428 }
2429}
2430bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) capability flags (bitmap)."] pub struct GimbalDeviceCapFlags : u16 { # [doc = "Gimbal device supports a retracted position."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Gimbal device supports a horizontal, forward looking position, stabilized."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Gimbal device supports rotating around roll axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Gimbal device supports to follow a roll angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Gimbal device supports rotating around pitch axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Gimbal device supports to follow a pitch angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Gimbal device supports rotating around yaw axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Gimbal device supports yawing/panning infinitely (e.g. using slip disk)."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; } }
2431impl GimbalDeviceCapFlags {
2432 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT;
2433}
2434impl Default for GimbalDeviceCapFlags {
2435 fn default() -> Self {
2436 Self::DEFAULT
2437 }
2438}
2439bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration."] pub struct PositionTargetTypemask : u16 { # [doc = "Ignore position x"] const POSITION_TARGET_TYPEMASK_X_IGNORE = 1 ; # [doc = "Ignore position y"] const POSITION_TARGET_TYPEMASK_Y_IGNORE = 2 ; # [doc = "Ignore position z"] const POSITION_TARGET_TYPEMASK_Z_IGNORE = 4 ; # [doc = "Ignore velocity x"] const POSITION_TARGET_TYPEMASK_VX_IGNORE = 8 ; # [doc = "Ignore velocity y"] const POSITION_TARGET_TYPEMASK_VY_IGNORE = 16 ; # [doc = "Ignore velocity z"] const POSITION_TARGET_TYPEMASK_VZ_IGNORE = 32 ; # [doc = "Ignore acceleration x"] const POSITION_TARGET_TYPEMASK_AX_IGNORE = 64 ; # [doc = "Ignore acceleration y"] const POSITION_TARGET_TYPEMASK_AY_IGNORE = 128 ; # [doc = "Ignore acceleration z"] const POSITION_TARGET_TYPEMASK_AZ_IGNORE = 256 ; # [doc = "Use force instead of acceleration"] const POSITION_TARGET_TYPEMASK_FORCE_SET = 512 ; # [doc = "Ignore yaw"] const POSITION_TARGET_TYPEMASK_YAW_IGNORE = 1024 ; # [doc = "Ignore yaw rate"] const POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = 2048 ; } }
2440impl PositionTargetTypemask {
2441 pub const DEFAULT: Self = Self::POSITION_TARGET_TYPEMASK_X_IGNORE;
2442}
2443impl Default for PositionTargetTypemask {
2444 fn default() -> Self {
2445 Self::DEFAULT
2446 }
2447}
2448#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2449#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2450#[cfg_attr(feature = "serde", serde(tag = "type"))]
2451#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2452#[repr(u32)]
2453pub enum MavOdidStatus {
2454 #[doc = "The status of the (UA) Unmanned Aircraft is undefined."]
2455 MAV_ODID_STATUS_UNDECLARED = 0,
2456 #[doc = "The UA is on the ground."]
2457 MAV_ODID_STATUS_GROUND = 1,
2458 #[doc = "The UA is in the air."]
2459 MAV_ODID_STATUS_AIRBORNE = 2,
2460 #[doc = "The UA is having an emergency."]
2461 MAV_ODID_STATUS_EMERGENCY = 3,
2462 #[doc = "The remote ID system is failing or unreliable in some way."]
2463 MAV_ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE = 4,
2464}
2465impl MavOdidStatus {
2466 pub const DEFAULT: Self = Self::MAV_ODID_STATUS_UNDECLARED;
2467}
2468impl Default for MavOdidStatus {
2469 fn default() -> Self {
2470 Self::DEFAULT
2471 }
2472}
2473#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2474#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2475#[cfg_attr(feature = "serde", serde(tag = "type"))]
2476#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2477#[repr(u32)]
2478pub enum MavlinkDataStreamType {
2479 MAVLINK_DATA_STREAM_IMG_JPEG = 0,
2480 MAVLINK_DATA_STREAM_IMG_BMP = 1,
2481 MAVLINK_DATA_STREAM_IMG_RAW8U = 2,
2482 MAVLINK_DATA_STREAM_IMG_RAW32U = 3,
2483 MAVLINK_DATA_STREAM_IMG_PGM = 4,
2484 MAVLINK_DATA_STREAM_IMG_PNG = 5,
2485}
2486impl MavlinkDataStreamType {
2487 pub const DEFAULT: Self = Self::MAVLINK_DATA_STREAM_IMG_JPEG;
2488}
2489impl Default for MavlinkDataStreamType {
2490 fn default() -> Self {
2491 Self::DEFAULT
2492 }
2493}
2494bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for gimbal device (lower level) operation."] pub struct GimbalDeviceFlags : u16 { # [doc = "Set to retracted safe position (no stabilization), takes precedence over all other flags."] const GIMBAL_DEVICE_FLAGS_RETRACT = 1 ; # [doc = "Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation."] const GIMBAL_DEVICE_FLAGS_NEUTRAL = 2 ; # [doc = "Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_ROLL_LOCK = 4 ; # [doc = "Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_PITCH_LOCK = 8 ; # [doc = "Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_LOCK = 16 ; # [doc = "Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored)."] const GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored."] const GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation."] const GIMBAL_DEVICE_FLAGS_RC_MIXED = 512 ; } }
2495impl GimbalDeviceFlags {
2496 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_FLAGS_RETRACT;
2497}
2498impl Default for GimbalDeviceFlags {
2499 fn default() -> Self {
2500 Self::DEFAULT
2501 }
2502}
2503bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for the global position report."] pub struct UtmDataAvailFlags : u8 { # [doc = "The field time contains valid data."] const UTM_DATA_AVAIL_FLAGS_TIME_VALID = 1 ; # [doc = "The field uas_id contains valid data."] const UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE = 2 ; # [doc = "The fields lat, lon and h_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE = 4 ; # [doc = "The fields alt and v_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE = 8 ; # [doc = "The field relative_alt contains valid data."] const UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE = 16 ; # [doc = "The fields vx and vy contain valid data."] const UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE = 32 ; # [doc = "The field vz contains valid data."] const UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE = 64 ; # [doc = "The fields next_lat, next_lon and next_alt contain valid data."] const UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE = 128 ; } }
2504impl UtmDataAvailFlags {
2505 pub const DEFAULT: Self = Self::UTM_DATA_AVAIL_FLAGS_TIME_VALID;
2506}
2507impl Default for UtmDataAvailFlags {
2508 fn default() -> Self {
2509 Self::DEFAULT
2510 }
2511}
2512#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2513#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2514#[cfg_attr(feature = "serde", serde(tag = "type"))]
2515#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2516#[repr(u32)]
2517#[doc = "Generalized UAVCAN node mode"]
2518pub enum UavcanNodeMode {
2519 #[doc = "The node is performing its primary functions."]
2520 UAVCAN_NODE_MODE_OPERATIONAL = 0,
2521 #[doc = "The node is initializing; this mode is entered immediately after startup."]
2522 UAVCAN_NODE_MODE_INITIALIZATION = 1,
2523 #[doc = "The node is under maintenance."]
2524 UAVCAN_NODE_MODE_MAINTENANCE = 2,
2525 #[doc = "The node is in the process of updating its software."]
2526 UAVCAN_NODE_MODE_SOFTWARE_UPDATE = 3,
2527 #[doc = "The node is no longer available online."]
2528 UAVCAN_NODE_MODE_OFFLINE = 7,
2529}
2530impl UavcanNodeMode {
2531 pub const DEFAULT: Self = Self::UAVCAN_NODE_MODE_OPERATIONAL;
2532}
2533impl Default for UavcanNodeMode {
2534 fn default() -> Self {
2535 Self::DEFAULT
2536 }
2537}
2538#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2539#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2540#[cfg_attr(feature = "serde", serde(tag = "type"))]
2541#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2542#[repr(u32)]
2543pub enum CanFilterOp {
2544 CAN_FILTER_REPLACE = 0,
2545 CAN_FILTER_ADD = 1,
2546 CAN_FILTER_REMOVE = 2,
2547}
2548impl CanFilterOp {
2549 pub const DEFAULT: Self = Self::CAN_FILTER_REPLACE;
2550}
2551impl Default for CanFilterOp {
2552 fn default() -> Self {
2553 Self::DEFAULT
2554 }
2555}
2556#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2557#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2558#[cfg_attr(feature = "serde", serde(tag = "type"))]
2559#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2560#[repr(u32)]
2561#[doc = "Source of information about this collision."]
2562pub enum MavCollisionSrc {
2563 #[doc = "ID field references ADSB_VEHICLE packets"]
2564 MAV_COLLISION_SRC_ADSB = 0,
2565 #[doc = "ID field references MAVLink SRC ID"]
2566 MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT = 1,
2567}
2568impl MavCollisionSrc {
2569 pub const DEFAULT: Self = Self::MAV_COLLISION_SRC_ADSB;
2570}
2571impl Default for MavCollisionSrc {
2572 fn default() -> Self {
2573 Self::DEFAULT
2574 }
2575}
2576#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2577#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2578#[cfg_attr(feature = "serde", serde(tag = "type"))]
2579#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2580#[repr(u32)]
2581pub enum MavOdidArmStatus {
2582 #[doc = "Passing arming checks."]
2583 MAV_ODID_ARM_STATUS_GOOD_TO_ARM = 0,
2584 #[doc = "Generic arming failure, see error string for details."]
2585 MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC = 1,
2586}
2587impl MavOdidArmStatus {
2588 pub const DEFAULT: Self = Self::MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
2589}
2590impl Default for MavOdidArmStatus {
2591 fn default() -> Self {
2592 Self::DEFAULT
2593 }
2594}
2595#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2596#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2597#[cfg_attr(feature = "serde", serde(tag = "type"))]
2598#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2599#[repr(u32)]
2600pub enum MavOdidClassEu {
2601 #[doc = "The class for the UA, according to the EU specification, is undeclared."]
2602 MAV_ODID_CLASS_EU_UNDECLARED = 0,
2603 #[doc = "The class for the UA, according to the EU specification, is Class 0."]
2604 MAV_ODID_CLASS_EU_CLASS_0 = 1,
2605 #[doc = "The class for the UA, according to the EU specification, is Class 1."]
2606 MAV_ODID_CLASS_EU_CLASS_1 = 2,
2607 #[doc = "The class for the UA, according to the EU specification, is Class 2."]
2608 MAV_ODID_CLASS_EU_CLASS_2 = 3,
2609 #[doc = "The class for the UA, according to the EU specification, is Class 3."]
2610 MAV_ODID_CLASS_EU_CLASS_3 = 4,
2611 #[doc = "The class for the UA, according to the EU specification, is Class 4."]
2612 MAV_ODID_CLASS_EU_CLASS_4 = 5,
2613 #[doc = "The class for the UA, according to the EU specification, is Class 5."]
2614 MAV_ODID_CLASS_EU_CLASS_5 = 6,
2615 #[doc = "The class for the UA, according to the EU specification, is Class 6."]
2616 MAV_ODID_CLASS_EU_CLASS_6 = 7,
2617}
2618impl MavOdidClassEu {
2619 pub const DEFAULT: Self = Self::MAV_ODID_CLASS_EU_UNDECLARED;
2620}
2621impl Default for MavOdidClassEu {
2622 fn default() -> Self {
2623 Self::DEFAULT
2624 }
2625}
2626bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in ESTIMATOR_STATUS message"] pub struct EstimatorStatusFlags : u16 { # [doc = "True if the attitude estimate is good"] const ESTIMATOR_ATTITUDE = 1 ; # [doc = "True if the horizontal velocity estimate is good"] const ESTIMATOR_VELOCITY_HORIZ = 2 ; # [doc = "True if the vertical velocity estimate is good"] const ESTIMATOR_VELOCITY_VERT = 4 ; # [doc = "True if the horizontal position (relative) estimate is good"] const ESTIMATOR_POS_HORIZ_REL = 8 ; # [doc = "True if the horizontal position (absolute) estimate is good"] const ESTIMATOR_POS_HORIZ_ABS = 16 ; # [doc = "True if the vertical position (absolute) estimate is good"] const ESTIMATOR_POS_VERT_ABS = 32 ; # [doc = "True if the vertical position (above ground) estimate is good"] const ESTIMATOR_POS_VERT_AGL = 64 ; # [doc = "True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)"] const ESTIMATOR_CONST_POS_MODE = 128 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_REL = 256 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_ABS = 512 ; # [doc = "True if the EKF has detected a GPS glitch"] const ESTIMATOR_GPS_GLITCH = 1024 ; # [doc = "True if the EKF has detected bad accelerometer data"] const ESTIMATOR_ACCEL_ERROR = 2048 ; } }
2627impl EstimatorStatusFlags {
2628 pub const DEFAULT: Self = Self::ESTIMATOR_ATTITUDE;
2629}
2630impl Default for EstimatorStatusFlags {
2631 fn default() -> Self {
2632 Self::DEFAULT
2633 }
2634}
2635#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2636#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2637#[cfg_attr(feature = "serde", serde(tag = "type"))]
2638#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2639#[repr(u32)]
2640pub enum NavVtolLandOptions {
2641 #[doc = "Default autopilot landing behaviour."]
2642 NAV_VTOL_LAND_OPTIONS_DEFAULT = 0,
2643 #[doc = "Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground. The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.)."]
2644 NAV_VTOL_LAND_OPTIONS_FW_DESCENT = 1,
2645 #[doc = "Land in multicopter mode on reaching the landing coordinates (the whole landing is by \"hover descent\")."]
2646 NAV_VTOL_LAND_OPTIONS_HOVER_DESCENT = 2,
2647}
2648impl NavVtolLandOptions {
2649 pub const DEFAULT: Self = Self::NAV_VTOL_LAND_OPTIONS_DEFAULT;
2650}
2651impl Default for NavVtolLandOptions {
2652 fn default() -> Self {
2653 Self::DEFAULT
2654 }
2655}
2656#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2657#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2658#[cfg_attr(feature = "serde", serde(tag = "type"))]
2659#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2660#[repr(u32)]
2661#[doc = "RC type. Used in MAV_CMD_START_RX_PAIR."]
2662pub enum RcType {
2663 #[doc = "Spektrum"]
2664 RC_TYPE_SPEKTRUM = 0,
2665 #[doc = "CRSF"]
2666 RC_TYPE_CRSF = 1,
2667}
2668impl RcType {
2669 pub const DEFAULT: Self = Self::RC_TYPE_SPEKTRUM;
2670}
2671impl Default for RcType {
2672 fn default() -> Self {
2673 Self::DEFAULT
2674 }
2675}
2676#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2677#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2678#[cfg_attr(feature = "serde", serde(tag = "type"))]
2679#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2680#[repr(u32)]
2681#[doc = "Modes of illuminator"]
2682pub enum IlluminatorMode {
2683 #[doc = "Illuminator mode is not specified/unknown"]
2684 ILLUMINATOR_MODE_UNKNOWN = 0,
2685 #[doc = "Illuminator behavior is controlled by MAV_CMD_DO_ILLUMINATOR_CONFIGURE settings"]
2686 ILLUMINATOR_MODE_INTERNAL_CONTROL = 1,
2687 #[doc = "Illuminator behavior is controlled by external factors: e.g. an external hardware signal"]
2688 ILLUMINATOR_MODE_EXTERNAL_SYNC = 2,
2689}
2690impl IlluminatorMode {
2691 pub const DEFAULT: Self = Self::ILLUMINATOR_MODE_UNKNOWN;
2692}
2693impl Default for IlluminatorMode {
2694 fn default() -> Self {
2695 Self::DEFAULT
2696 }
2697}
2698#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2699#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2700#[cfg_attr(feature = "serde", serde(tag = "type"))]
2701#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2702#[repr(u32)]
2703#[doc = "RC sub-type of types defined in RC_TYPE. Used in MAV_CMD_START_RX_PAIR. Ignored if value does not correspond to the set RC_TYPE."]
2704pub enum RcSubType {
2705 #[doc = "Spektrum DSM2"]
2706 RC_SUB_TYPE_SPEKTRUM_DSM2 = 0,
2707 #[doc = "Spektrum DSMX"]
2708 RC_SUB_TYPE_SPEKTRUM_DSMX = 1,
2709 #[doc = "Spektrum DSMX8"]
2710 RC_SUB_TYPE_SPEKTRUM_DSMX8 = 2,
2711}
2712impl RcSubType {
2713 pub const DEFAULT: Self = Self::RC_SUB_TYPE_SPEKTRUM_DSM2;
2714}
2715impl Default for RcSubType {
2716 fn default() -> Self {
2717 Self::DEFAULT
2718 }
2719}
2720#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2721#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2722#[cfg_attr(feature = "serde", serde(tag = "type"))]
2723#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2724#[repr(u32)]
2725#[doc = "Video stream encodings"]
2726pub enum VideoStreamEncoding {
2727 #[doc = "Stream encoding is unknown"]
2728 VIDEO_STREAM_ENCODING_UNKNOWN = 0,
2729 #[doc = "Stream encoding is H.264"]
2730 VIDEO_STREAM_ENCODING_H264 = 1,
2731 #[doc = "Stream encoding is H.265"]
2732 VIDEO_STREAM_ENCODING_H265 = 2,
2733}
2734impl VideoStreamEncoding {
2735 pub const DEFAULT: Self = Self::VIDEO_STREAM_ENCODING_UNKNOWN;
2736}
2737impl Default for VideoStreamEncoding {
2738 fn default() -> Self {
2739 Self::DEFAULT
2740 }
2741}
2742#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2743#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2744#[cfg_attr(feature = "serde", serde(tag = "type"))]
2745#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2746#[repr(u32)]
2747#[doc = "Airborne status of UAS."]
2748pub enum UtmFlightState {
2749 #[doc = "The flight state can't be determined."]
2750 UTM_FLIGHT_STATE_UNKNOWN = 1,
2751 #[doc = "UAS on ground."]
2752 UTM_FLIGHT_STATE_GROUND = 2,
2753 #[doc = "UAS airborne."]
2754 UTM_FLIGHT_STATE_AIRBORNE = 3,
2755 #[doc = "UAS is in an emergency flight state."]
2756 UTM_FLIGHT_STATE_EMERGENCY = 16,
2757 #[doc = "UAS has no active controls."]
2758 UTM_FLIGHT_STATE_NOCTRL = 32,
2759}
2760impl UtmFlightState {
2761 pub const DEFAULT: Self = Self::UTM_FLIGHT_STATE_UNKNOWN;
2762}
2763impl Default for UtmFlightState {
2764 fn default() -> Self {
2765 Self::DEFAULT
2766 }
2767}
2768#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2769#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2770#[cfg_attr(feature = "serde", serde(tag = "type"))]
2771#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2772#[repr(u32)]
2773#[doc = "Flags to indicate the status of camera storage."]
2774pub enum StorageStatus {
2775 #[doc = "Storage is missing (no microSD card loaded for example.)"]
2776 STORAGE_STATUS_EMPTY = 0,
2777 #[doc = "Storage present but unformatted."]
2778 STORAGE_STATUS_UNFORMATTED = 1,
2779 #[doc = "Storage present and ready."]
2780 STORAGE_STATUS_READY = 2,
2781 #[doc = "Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored."]
2782 STORAGE_STATUS_NOT_SUPPORTED = 3,
2783}
2784impl StorageStatus {
2785 pub const DEFAULT: Self = Self::STORAGE_STATUS_EMPTY;
2786}
2787impl Default for StorageStatus {
2788 fn default() -> Self {
2789 Self::DEFAULT
2790 }
2791}
2792bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message."] pub struct MavSysStatusSensor : u32 { # [doc = "0x01 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 ; # [doc = "0x02 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 ; # [doc = "0x04 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG = 4 ; # [doc = "0x08 absolute pressure"] const MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 ; # [doc = "0x10 differential pressure"] const MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 ; # [doc = "0x20 GPS"] const MAV_SYS_STATUS_SENSOR_GPS = 32 ; # [doc = "0x40 optical flow"] const MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 ; # [doc = "0x80 computer vision position"] const MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 ; # [doc = "0x100 laser based position"] const MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 ; # [doc = "0x200 external ground truth (Vicon or Leica)"] const MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 ; # [doc = "0x400 3D angular rate control"] const MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 ; # [doc = "0x800 attitude stabilization"] const MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 ; # [doc = "0x1000 yaw position"] const MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 ; # [doc = "0x2000 z/altitude control"] const MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 ; # [doc = "0x4000 x/y position control"] const MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 ; # [doc = "0x8000 motor outputs / control"] const MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 ; # [doc = "0x10000 RC receiver"] const MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 ; # [doc = "0x20000 2nd 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 ; # [doc = "0x40000 2nd 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 ; # [doc = "0x80000 2nd 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 ; # [doc = "0x100000 geofence"] const MAV_SYS_STATUS_GEOFENCE = 1048576 ; # [doc = "0x200000 AHRS subsystem health"] const MAV_SYS_STATUS_AHRS = 2097152 ; # [doc = "0x400000 Terrain subsystem health"] const MAV_SYS_STATUS_TERRAIN = 4194304 ; # [doc = "0x800000 Motors are reversed"] const MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 ; # [doc = "0x1000000 Logging"] const MAV_SYS_STATUS_LOGGING = 16777216 ; # [doc = "0x2000000 Battery"] const MAV_SYS_STATUS_SENSOR_BATTERY = 33554432 ; # [doc = "0x4000000 Proximity"] const MAV_SYS_STATUS_SENSOR_PROXIMITY = 67108864 ; # [doc = "0x8000000 Satellite Communication"] const MAV_SYS_STATUS_SENSOR_SATCOM = 134217728 ; # [doc = "0x10000000 pre-arm check status. Always healthy when armed"] const MAV_SYS_STATUS_PREARM_CHECK = 268435456 ; # [doc = "0x20000000 Avoidance/collision prevention"] const MAV_SYS_STATUS_OBSTACLE_AVOIDANCE = 536870912 ; # [doc = "0x40000000 propulsion (actuator, esc, motor or propellor)"] const MAV_SYS_STATUS_SENSOR_PROPULSION = 1073741824 ; # [doc = "0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)"] const MAV_SYS_STATUS_EXTENSION_USED = 2147483648 ; } }
2793impl MavSysStatusSensor {
2794 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_SENSOR_3D_GYRO;
2795}
2796impl Default for MavSysStatusSensor {
2797 fn default() -> Self {
2798 Self::DEFAULT
2799 }
2800}
2801#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2802#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2803#[cfg_attr(feature = "serde", serde(tag = "type"))]
2804#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2805#[repr(u32)]
2806#[doc = "Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages."]
2807pub enum MavMountMode {
2808 #[doc = "Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization"]
2809 MAV_MOUNT_MODE_RETRACT = 0,
2810 #[doc = "Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory."]
2811 MAV_MOUNT_MODE_NEUTRAL = 1,
2812 #[doc = "Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization"]
2813 MAV_MOUNT_MODE_MAVLINK_TARGETING = 2,
2814 #[doc = "Load neutral position and start RC Roll,Pitch,Yaw control with stabilization"]
2815 MAV_MOUNT_MODE_RC_TARGETING = 3,
2816 #[doc = "Load neutral position and start to point to Lat,Lon,Alt"]
2817 MAV_MOUNT_MODE_GPS_POINT = 4,
2818 #[doc = "Gimbal tracks system with specified system ID"]
2819 MAV_MOUNT_MODE_SYSID_TARGET = 5,
2820 #[doc = "Gimbal tracks home position"]
2821 MAV_MOUNT_MODE_HOME_LOCATION = 6,
2822}
2823impl MavMountMode {
2824 pub const DEFAULT: Self = Self::MAV_MOUNT_MODE_RETRACT;
2825}
2826impl Default for MavMountMode {
2827 fn default() -> Self {
2828 Self::DEFAULT
2829 }
2830}
2831#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2832#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2833#[cfg_attr(feature = "serde", serde(tag = "type"))]
2834#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2835#[repr(u32)]
2836#[doc = "Gripper actions."]
2837pub enum GripperActions {
2838 #[doc = "Gripper release cargo."]
2839 GRIPPER_ACTION_RELEASE = 0,
2840 #[doc = "Gripper grab onto cargo."]
2841 GRIPPER_ACTION_GRAB = 1,
2842}
2843impl GripperActions {
2844 pub const DEFAULT: Self = Self::GRIPPER_ACTION_RELEASE;
2845}
2846impl Default for GripperActions {
2847 fn default() -> Self {
2848 Self::DEFAULT
2849 }
2850}
2851#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2852#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2853#[cfg_attr(feature = "serde", serde(tag = "type"))]
2854#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2855#[repr(u32)]
2856#[doc = "Video stream types"]
2857pub enum VideoStreamType {
2858 #[doc = "Stream is RTSP"]
2859 VIDEO_STREAM_TYPE_RTSP = 0,
2860 #[doc = "Stream is RTP UDP (URI gives the port number)"]
2861 VIDEO_STREAM_TYPE_RTPUDP = 1,
2862 #[doc = "Stream is MPEG on TCP"]
2863 VIDEO_STREAM_TYPE_TCP_MPEG = 2,
2864 #[doc = "Stream is MPEG TS (URI gives the port number)"]
2865 VIDEO_STREAM_TYPE_MPEG_TS = 3,
2866}
2867impl VideoStreamType {
2868 pub const DEFAULT: Self = Self::VIDEO_STREAM_TYPE_RTSP;
2869}
2870impl Default for VideoStreamType {
2871 fn default() -> Self {
2872 Self::DEFAULT
2873 }
2874}
2875#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2876#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2877#[cfg_attr(feature = "serde", serde(tag = "type"))]
2878#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2879#[repr(u32)]
2880pub enum MavOdidTimeAcc {
2881 #[doc = "The timestamp accuracy is unknown."]
2882 MAV_ODID_TIME_ACC_UNKNOWN = 0,
2883 #[doc = "The timestamp accuracy is smaller than or equal to 0.1 second."]
2884 MAV_ODID_TIME_ACC_0_1_SECOND = 1,
2885 #[doc = "The timestamp accuracy is smaller than or equal to 0.2 second."]
2886 MAV_ODID_TIME_ACC_0_2_SECOND = 2,
2887 #[doc = "The timestamp accuracy is smaller than or equal to 0.3 second."]
2888 MAV_ODID_TIME_ACC_0_3_SECOND = 3,
2889 #[doc = "The timestamp accuracy is smaller than or equal to 0.4 second."]
2890 MAV_ODID_TIME_ACC_0_4_SECOND = 4,
2891 #[doc = "The timestamp accuracy is smaller than or equal to 0.5 second."]
2892 MAV_ODID_TIME_ACC_0_5_SECOND = 5,
2893 #[doc = "The timestamp accuracy is smaller than or equal to 0.6 second."]
2894 MAV_ODID_TIME_ACC_0_6_SECOND = 6,
2895 #[doc = "The timestamp accuracy is smaller than or equal to 0.7 second."]
2896 MAV_ODID_TIME_ACC_0_7_SECOND = 7,
2897 #[doc = "The timestamp accuracy is smaller than or equal to 0.8 second."]
2898 MAV_ODID_TIME_ACC_0_8_SECOND = 8,
2899 #[doc = "The timestamp accuracy is smaller than or equal to 0.9 second."]
2900 MAV_ODID_TIME_ACC_0_9_SECOND = 9,
2901 #[doc = "The timestamp accuracy is smaller than or equal to 1.0 second."]
2902 MAV_ODID_TIME_ACC_1_0_SECOND = 10,
2903 #[doc = "The timestamp accuracy is smaller than or equal to 1.1 second."]
2904 MAV_ODID_TIME_ACC_1_1_SECOND = 11,
2905 #[doc = "The timestamp accuracy is smaller than or equal to 1.2 second."]
2906 MAV_ODID_TIME_ACC_1_2_SECOND = 12,
2907 #[doc = "The timestamp accuracy is smaller than or equal to 1.3 second."]
2908 MAV_ODID_TIME_ACC_1_3_SECOND = 13,
2909 #[doc = "The timestamp accuracy is smaller than or equal to 1.4 second."]
2910 MAV_ODID_TIME_ACC_1_4_SECOND = 14,
2911 #[doc = "The timestamp accuracy is smaller than or equal to 1.5 second."]
2912 MAV_ODID_TIME_ACC_1_5_SECOND = 15,
2913}
2914impl MavOdidTimeAcc {
2915 pub const DEFAULT: Self = Self::MAV_ODID_TIME_ACC_UNKNOWN;
2916}
2917impl Default for MavOdidTimeAcc {
2918 fn default() -> Self {
2919 Self::DEFAULT
2920 }
2921}
2922#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2923#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2924#[cfg_attr(feature = "serde", serde(tag = "type"))]
2925#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2926#[repr(u32)]
2927pub enum MavOdidAuthType {
2928 #[doc = "No authentication type is specified."]
2929 MAV_ODID_AUTH_TYPE_NONE = 0,
2930 #[doc = "Signature for the UAS (Unmanned Aircraft System) ID."]
2931 MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE = 1,
2932 #[doc = "Signature for the Operator ID."]
2933 MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE = 2,
2934 #[doc = "Signature for the entire message set."]
2935 MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE = 3,
2936 #[doc = "Authentication is provided by Network Remote ID."]
2937 MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID = 4,
2938 #[doc = "The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO."]
2939 MAV_ODID_AUTH_TYPE_SPECIFIC_AUTHENTICATION = 5,
2940}
2941impl MavOdidAuthType {
2942 pub const DEFAULT: Self = Self::MAV_ODID_AUTH_TYPE_NONE;
2943}
2944impl Default for MavOdidAuthType {
2945 fn default() -> Self {
2946 Self::DEFAULT
2947 }
2948}
2949#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2950#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2951#[cfg_attr(feature = "serde", serde(tag = "type"))]
2952#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2953#[repr(u32)]
2954#[doc = "Specifies the conditions under which the MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command should be accepted."]
2955pub enum RebootShutdownConditions {
2956 #[doc = "Reboot/Shutdown only if allowed by safety checks, such as being landed."]
2957 REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED = 0,
2958 #[doc = "Force reboot/shutdown of the autopilot/component regardless of system state."]
2959 REBOOT_SHUTDOWN_CONDITIONS_FORCE = 20190226,
2960}
2961impl RebootShutdownConditions {
2962 pub const DEFAULT: Self = Self::REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED;
2963}
2964impl Default for RebootShutdownConditions {
2965 fn default() -> Self {
2966 Self::DEFAULT
2967 }
2968}
2969#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2970#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2971#[cfg_attr(feature = "serde", serde(tag = "type"))]
2972#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2973#[repr(u32)]
2974#[doc = "Reason for an event error response."]
2975pub enum MavEventErrorReason {
2976 #[doc = "The requested event is not available (anymore)."]
2977 MAV_EVENT_ERROR_REASON_UNAVAILABLE = 0,
2978}
2979impl MavEventErrorReason {
2980 pub const DEFAULT: Self = Self::MAV_EVENT_ERROR_REASON_UNAVAILABLE;
2981}
2982impl Default for MavEventErrorReason {
2983 fn default() -> Self {
2984 Self::DEFAULT
2985 }
2986}
2987#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2988#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2989#[cfg_attr(feature = "serde", serde(tag = "type"))]
2990#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2991#[repr(u32)]
2992#[doc = "A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages."]
2993pub enum MavDataStream {
2994 #[doc = "Enable all data streams"]
2995 MAV_DATA_STREAM_ALL = 0,
2996 #[doc = "Enable IMU_RAW, GPS_RAW, GPS_STATUS packets."]
2997 MAV_DATA_STREAM_RAW_SENSORS = 1,
2998 #[doc = "Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS"]
2999 MAV_DATA_STREAM_EXTENDED_STATUS = 2,
3000 #[doc = "Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW"]
3001 MAV_DATA_STREAM_RC_CHANNELS = 3,
3002 #[doc = "Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT."]
3003 MAV_DATA_STREAM_RAW_CONTROLLER = 4,
3004 #[doc = "Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages."]
3005 MAV_DATA_STREAM_POSITION = 6,
3006 #[doc = "Dependent on the autopilot"]
3007 MAV_DATA_STREAM_EXTRA1 = 10,
3008 #[doc = "Dependent on the autopilot"]
3009 MAV_DATA_STREAM_EXTRA2 = 11,
3010 #[doc = "Dependent on the autopilot"]
3011 MAV_DATA_STREAM_EXTRA3 = 12,
3012}
3013impl MavDataStream {
3014 pub const DEFAULT: Self = Self::MAV_DATA_STREAM_ALL;
3015}
3016impl Default for MavDataStream {
3017 fn default() -> Self {
3018 Self::DEFAULT
3019 }
3020}
3021#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3022#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3023#[cfg_attr(feature = "serde", serde(tag = "type"))]
3024#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3025#[repr(u32)]
3026#[doc = "Winch actions."]
3027pub enum WinchActions {
3028 #[doc = "Allow motor to freewheel."]
3029 WINCH_RELAXED = 0,
3030 #[doc = "Wind or unwind specified length of line, optionally using specified rate."]
3031 WINCH_RELATIVE_LENGTH_CONTROL = 1,
3032 #[doc = "Wind or unwind line at specified rate."]
3033 WINCH_RATE_CONTROL = 2,
3034 #[doc = "Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored."]
3035 WINCH_LOCK = 3,
3036 #[doc = "Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored."]
3037 WINCH_DELIVER = 4,
3038 #[doc = "Engage motor and hold current position. Only action and instance command parameters are used, others are ignored."]
3039 WINCH_HOLD = 5,
3040 #[doc = "Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored."]
3041 WINCH_RETRACT = 6,
3042 #[doc = "Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored."]
3043 WINCH_LOAD_LINE = 7,
3044 #[doc = "Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored."]
3045 WINCH_ABANDON_LINE = 8,
3046 #[doc = "Spools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored"]
3047 WINCH_LOAD_PAYLOAD = 9,
3048}
3049impl WinchActions {
3050 pub const DEFAULT: Self = Self::WINCH_RELAXED;
3051}
3052impl Default for WinchActions {
3053 fn default() -> Self {
3054 Self::DEFAULT
3055 }
3056}
3057#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3058#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3059#[cfg_attr(feature = "serde", serde(tag = "type"))]
3060#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3061#[repr(u32)]
3062#[doc = "Yaw behaviour during orbit flight."]
3063pub enum OrbitYawBehaviour {
3064 #[doc = "Vehicle front points to the center (default)."]
3065 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0,
3066 #[doc = "Vehicle front holds heading when message received."]
3067 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1,
3068 #[doc = "Yaw uncontrolled."]
3069 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2,
3070 #[doc = "Vehicle front follows flight path (tangential to circle)."]
3071 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3,
3072 #[doc = "Yaw controlled by RC input."]
3073 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4,
3074 #[doc = "Vehicle uses current yaw behaviour (unchanged). The vehicle-default yaw behaviour is used if this value is specified when orbit is first commanded."]
3075 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5,
3076}
3077impl OrbitYawBehaviour {
3078 pub const DEFAULT: Self = Self::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER;
3079}
3080impl Default for OrbitYawBehaviour {
3081 fn default() -> Self {
3082 Self::DEFAULT
3083 }
3084}
3085bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Illuminator module error flags (bitmap, 0 means no error)"] pub struct IlluminatorErrorFlags : u32 { # [doc = "Illuminator thermal throttling error."] const ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING = 1 ; # [doc = "Illuminator over temperature shutdown error."] const ILLUMINATOR_ERROR_FLAGS_OVER_TEMPERATURE_SHUTDOWN = 2 ; # [doc = "Illuminator thermistor failure."] const ILLUMINATOR_ERROR_FLAGS_THERMISTOR_FAILURE = 4 ; } }
3086impl IlluminatorErrorFlags {
3087 pub const DEFAULT: Self = Self::ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING;
3088}
3089impl Default for IlluminatorErrorFlags {
3090 fn default() -> Self {
3091 Self::DEFAULT
3092 }
3093}
3094bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report failure cases over the high latency telemetry."] pub struct HlFailureFlag : u16 { # [doc = "GPS failure."] const HL_FAILURE_FLAG_GPS = 1 ; # [doc = "Differential pressure sensor failure."] const HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE = 2 ; # [doc = "Absolute pressure sensor failure."] const HL_FAILURE_FLAG_ABSOLUTE_PRESSURE = 4 ; # [doc = "Accelerometer sensor failure."] const HL_FAILURE_FLAG_3D_ACCEL = 8 ; # [doc = "Gyroscope sensor failure."] const HL_FAILURE_FLAG_3D_GYRO = 16 ; # [doc = "Magnetometer sensor failure."] const HL_FAILURE_FLAG_3D_MAG = 32 ; # [doc = "Terrain subsystem failure."] const HL_FAILURE_FLAG_TERRAIN = 64 ; # [doc = "Battery failure/critical low battery."] const HL_FAILURE_FLAG_BATTERY = 128 ; # [doc = "RC receiver failure/no RC connection."] const HL_FAILURE_FLAG_RC_RECEIVER = 256 ; # [doc = "Offboard link failure."] const HL_FAILURE_FLAG_OFFBOARD_LINK = 512 ; # [doc = "Engine failure."] const HL_FAILURE_FLAG_ENGINE = 1024 ; # [doc = "Geofence violation."] const HL_FAILURE_FLAG_GEOFENCE = 2048 ; # [doc = "Estimator failure, for example measurement rejection or large variances."] const HL_FAILURE_FLAG_ESTIMATOR = 4096 ; # [doc = "Mission failure."] const HL_FAILURE_FLAG_MISSION = 8192 ; } }
3095impl HlFailureFlag {
3096 pub const DEFAULT: Self = Self::HL_FAILURE_FLAG_GPS;
3097}
3098impl Default for HlFailureFlag {
3099 fn default() -> Self {
3100 Self::DEFAULT
3101 }
3102}
3103#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3104#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3105#[cfg_attr(feature = "serde", serde(tag = "type"))]
3106#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3107#[repr(u32)]
3108#[doc = "Flags to indicate the type of storage."]
3109pub enum StorageType {
3110 #[doc = "Storage type is not known."]
3111 STORAGE_TYPE_UNKNOWN = 0,
3112 #[doc = "Storage type is USB device."]
3113 STORAGE_TYPE_USB_STICK = 1,
3114 #[doc = "Storage type is SD card."]
3115 STORAGE_TYPE_SD = 2,
3116 #[doc = "Storage type is microSD card."]
3117 STORAGE_TYPE_MICROSD = 3,
3118 #[doc = "Storage type is CFast."]
3119 STORAGE_TYPE_CF = 4,
3120 #[doc = "Storage type is CFexpress."]
3121 STORAGE_TYPE_CFE = 5,
3122 #[doc = "Storage type is XQD."]
3123 STORAGE_TYPE_XQD = 6,
3124 #[doc = "Storage type is HD mass storage type."]
3125 STORAGE_TYPE_HD = 7,
3126 #[doc = "Storage type is other, not listed type."]
3127 STORAGE_TYPE_OTHER = 254,
3128}
3129impl StorageType {
3130 pub const DEFAULT: Self = Self::STORAGE_TYPE_UNKNOWN;
3131}
3132impl Default for StorageType {
3133 fn default() -> Self {
3134 Self::DEFAULT
3135 }
3136}
3137#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3138#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3139#[cfg_attr(feature = "serde", serde(tag = "type"))]
3140#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3141#[repr(u32)]
3142#[doc = "Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
3143pub enum PreflightStorageMissionAction {
3144 #[doc = "Read current mission data from persistent storage"]
3145 MISSION_READ_PERSISTENT = 0,
3146 #[doc = "Write current mission data to persistent storage"]
3147 MISSION_WRITE_PERSISTENT = 1,
3148 #[doc = "Erase all mission data stored on the vehicle (both persistent and volatile storage)"]
3149 MISSION_RESET_DEFAULT = 2,
3150}
3151impl PreflightStorageMissionAction {
3152 pub const DEFAULT: Self = Self::MISSION_READ_PERSISTENT;
3153}
3154impl Default for PreflightStorageMissionAction {
3155 fn default() -> Self {
3156 Self::DEFAULT
3157 }
3158}
3159#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3160#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3161#[cfg_attr(feature = "serde", serde(tag = "type"))]
3162#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3163#[repr(u32)]
3164#[doc = "Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See <https://mavlink.io/en/guide/xml_schema.html#MAV_CMD> for information about the structure of the MAV_CMD entries"]
3165pub enum MavCmd {
3166 #[doc = "Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION)."]
3167 MAV_CMD_NAV_WAYPOINT = 16,
3168 #[doc = "Loiter around this waypoint an unlimited amount of time"]
3169 MAV_CMD_NAV_LOITER_UNLIM = 17,
3170 #[doc = "Loiter around this waypoint for X turns"]
3171 MAV_CMD_NAV_LOITER_TURNS = 18,
3172 #[doc = "Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint."]
3173 MAV_CMD_NAV_LOITER_TIME = 19,
3174 #[doc = "Return to launch location"]
3175 MAV_CMD_NAV_RETURN_TO_LAUNCH = 20,
3176 #[doc = "Land at location."]
3177 MAV_CMD_NAV_LAND = 21,
3178 #[doc = "Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode."]
3179 MAV_CMD_NAV_TAKEOFF = 22,
3180 #[doc = "Land at local position (local frame only)"]
3181 MAV_CMD_NAV_LAND_LOCAL = 23,
3182 #[doc = "Takeoff from local position (local frame only)"]
3183 MAV_CMD_NAV_TAKEOFF_LOCAL = 24,
3184 #[doc = "Vehicle following, i.e. this waypoint represents the position of a moving vehicle"]
3185 MAV_CMD_NAV_FOLLOW = 25,
3186 #[doc = "Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached."]
3187 MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30,
3188 #[doc = "Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint."]
3189 MAV_CMD_NAV_LOITER_TO_ALT = 31,
3190 #[doc = "Begin following a target"]
3191 MAV_CMD_DO_FOLLOW = 32,
3192 #[doc = "Reposition the MAV after a follow target command has been sent"]
3193 MAV_CMD_DO_FOLLOW_REPOSITION = 33,
3194 #[doc = "Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults."]
3195 MAV_CMD_DO_ORBIT = 34,
3196 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
3197 MAV_CMD_NAV_ROI = 80,
3198 #[doc = "Control autonomous path planning on the MAV."]
3199 MAV_CMD_NAV_PATHPLANNING = 81,
3200 #[doc = "Navigate to waypoint using a spline path."]
3201 MAV_CMD_NAV_SPLINE_WAYPOINT = 82,
3202 #[doc = "Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.)."]
3203 MAV_CMD_NAV_VTOL_TAKEOFF = 84,
3204 #[doc = "Land using VTOL mode"]
3205 MAV_CMD_NAV_VTOL_LAND = 85,
3206 #[doc = "hand control over to an external controller"]
3207 MAV_CMD_NAV_GUIDED_ENABLE = 92,
3208 #[doc = "Delay the next navigation command a number of seconds or until a specified time"]
3209 MAV_CMD_NAV_DELAY = 93,
3210 #[doc = "Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload."]
3211 MAV_CMD_NAV_PAYLOAD_PLACE = 94,
3212 #[doc = "NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration"]
3213 MAV_CMD_NAV_LAST = 95,
3214 #[doc = "Delay mission state machine."]
3215 MAV_CMD_CONDITION_DELAY = 112,
3216 #[doc = "Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached."]
3217 MAV_CMD_CONDITION_CHANGE_ALT = 113,
3218 #[doc = "Delay mission state machine until within desired distance of next NAV point."]
3219 MAV_CMD_CONDITION_DISTANCE = 114,
3220 #[doc = "Reach a certain target angle."]
3221 MAV_CMD_CONDITION_YAW = 115,
3222 #[doc = "NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration"]
3223 MAV_CMD_CONDITION_LAST = 159,
3224 #[doc = "Set system mode."]
3225 MAV_CMD_DO_SET_MODE = 176,
3226 #[doc = "Jump to the desired command in the mission list. Repeat this action only the specified number of times"]
3227 MAV_CMD_DO_JUMP = 177,
3228 #[doc = "Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change"]
3229 MAV_CMD_DO_CHANGE_SPEED = 178,
3230 #[doc = "Sets the home position to either to the current position or a specified position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this command). Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
3231 MAV_CMD_DO_SET_HOME = 179,
3232 #[doc = "Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter."]
3233 MAV_CMD_DO_SET_PARAMETER = 180,
3234 #[doc = "Set a relay to a condition."]
3235 MAV_CMD_DO_SET_RELAY = 181,
3236 #[doc = "Cycle a relay on and off for a desired number of cycles with a desired period."]
3237 MAV_CMD_DO_REPEAT_RELAY = 182,
3238 #[doc = "Set a servo to a desired PWM value."]
3239 MAV_CMD_DO_SET_SERVO = 183,
3240 #[doc = "Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period."]
3241 MAV_CMD_DO_REPEAT_SERVO = 184,
3242 #[doc = "0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED."]
3243 MAV_CMD_DO_FLIGHTTERMINATION = 185,
3244 #[doc = "Change altitude set point."]
3245 MAV_CMD_DO_CHANGE_ALTITUDE = 186,
3246 #[doc = "Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter)."]
3247 MAV_CMD_DO_SET_ACTUATOR = 187,
3248 #[doc = "Mission item to specify the start of a failsafe/landing return-path segment (the end of the segment is the next MAV_CMD_DO_LAND_START item). A vehicle that is using missions for landing (e.g. in a return mode) will join the mission on the closest path of the return-path segment (instead of MAV_CMD_DO_LAND_START or the nearest waypoint). The main use case is to minimize the failsafe flight path in corridor missions, where the inbound/outbound paths are constrained (by geofences) to the same particular path. The MAV_CMD_NAV_RETURN_PATH_START would be placed at the start of the return path. If a failsafe occurs on the outbound path the vehicle will move to the nearest point on the return path (which is parallel for this kind of mission), effectively turning round and following the shortest path to landing. If a failsafe occurs on the inbound path the vehicle is already on the return segment and will continue to landing. The Latitude/Longitude/Altitude are optional, and may be set to 0 if not needed. If specified, the item defines the waypoint at which the return segment starts. If sent using as a command, the vehicle will perform a mission landing (using the land segment if defined) or reject the command if mission landings are not supported, or no mission landing is defined. When used as a command any position information in the command is ignored."]
3249 MAV_CMD_DO_RETURN_PATH_START = 188,
3250 #[doc = "Mission item to mark the start of a mission landing pattern, or a command to land with a mission landing pattern. When used in a mission, this is a marker for the start of a sequence of mission items that represent a landing pattern. It should be followed by a navigation item that defines the first waypoint of the landing sequence. The start marker positional params are used only for selecting what landing pattern to use if several are defined in the mission (the selected pattern will be the one with the marker position that is closest to the vehicle when a landing is commanded). If the marker item position has zero-values for latitude, longitude, and altitude, then landing pattern selection is instead based on the position of the first waypoint in the landing sequence. \t When sent as a command it triggers a landing using a mission landing pattern. \t The location parameters are not used in this case, and should be set to 0."]
3251 MAV_CMD_DO_LAND_START = 189,
3252 #[doc = "Mission command to perform a landing from a rally point."]
3253 MAV_CMD_DO_RALLY_LAND = 190,
3254 #[doc = "Mission command to safely abort an autonomous landing."]
3255 MAV_CMD_DO_GO_AROUND = 191,
3256 #[doc = "Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead)."]
3257 MAV_CMD_DO_REPOSITION = 192,
3258 #[doc = "If in a GPS controlled position mode, hold the current position or continue."]
3259 MAV_CMD_DO_PAUSE_CONTINUE = 193,
3260 #[doc = "Set moving direction to forward or reverse."]
3261 MAV_CMD_DO_SET_REVERSE = 194,
3262 #[doc = "Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message."]
3263 MAV_CMD_DO_SET_ROI_LOCATION = 195,
3264 #[doc = "Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
3265 MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196,
3266 #[doc = "Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position."]
3267 MAV_CMD_DO_SET_ROI_NONE = 197,
3268 #[doc = "Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
3269 MAV_CMD_DO_SET_ROI_SYSID = 198,
3270 #[doc = "Control onboard camera system."]
3271 MAV_CMD_DO_CONTROL_VIDEO = 200,
3272 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
3273 MAV_CMD_DO_SET_ROI = 201,
3274 #[doc = "Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
3275 MAV_CMD_DO_DIGICAM_CONFIGURE = 202,
3276 #[doc = "Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
3277 MAV_CMD_DO_DIGICAM_CONTROL = 203,
3278 #[doc = "Mission command to configure a camera or antenna mount"]
3279 MAV_CMD_DO_MOUNT_CONFIGURE = 204,
3280 #[doc = "Mission command to control a camera or antenna mount"]
3281 MAV_CMD_DO_MOUNT_CONTROL = 205,
3282 #[doc = "Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera."]
3283 MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206,
3284 #[doc = "Enable the geofence. This can be used in a mission or via the command protocol. The persistence/lifetime of the setting is undefined. Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission. Flight stacks typically reset the setting to system defaults on reboot."]
3285 MAV_CMD_DO_FENCE_ENABLE = 207,
3286 #[doc = "Mission item/command to release a parachute or enable/disable auto release."]
3287 MAV_CMD_DO_PARACHUTE = 208,
3288 #[doc = "Command to perform motor test."]
3289 MAV_CMD_DO_MOTOR_TEST = 209,
3290 #[doc = "Change to/from inverted flight."]
3291 MAV_CMD_DO_INVERTED_FLIGHT = 210,
3292 #[doc = "Mission command to operate a gripper."]
3293 MAV_CMD_DO_GRIPPER = 211,
3294 #[doc = "Enable/disable autotune."]
3295 MAV_CMD_DO_AUTOTUNE_ENABLE = 212,
3296 #[doc = "Sets a desired vehicle turn angle and speed change."]
3297 MAV_CMD_NAV_SET_YAW_SPEED = 213,
3298 #[doc = "Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera."]
3299 MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214,
3300 #[doc = "Mission command to control a camera or antenna mount, using a quaternion as reference."]
3301 MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220,
3302 #[doc = "set id of master controller"]
3303 MAV_CMD_DO_GUIDED_MASTER = 221,
3304 #[doc = "Set limits for external control"]
3305 MAV_CMD_DO_GUIDED_LIMITS = 222,
3306 #[doc = "Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines"]
3307 MAV_CMD_DO_ENGINE_CONTROL = 223,
3308 #[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. \t Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2). This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this command must not trigger a switch to mission mode. The mission may be \"reset\" using param2. Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`). Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode. \t The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item)."]
3309 MAV_CMD_DO_SET_MISSION_CURRENT = 224,
3310 #[doc = "NOP - This command is only used to mark the upper limit of the DO commands in the enumeration"]
3311 MAV_CMD_DO_LAST = 240,
3312 #[doc = "Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero."]
3313 MAV_CMD_PREFLIGHT_CALIBRATION = 241,
3314 #[doc = "Set sensor offsets. This command will be only accepted if in pre-flight mode."]
3315 MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242,
3316 #[doc = "Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named)."]
3317 MAV_CMD_PREFLIGHT_UAVCAN = 243,
3318 #[doc = "Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode."]
3319 MAV_CMD_PREFLIGHT_STORAGE = 245,
3320 #[doc = "Request the reboot or shutdown of system components."]
3321 MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246,
3322 #[doc = "Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position."]
3323 MAV_CMD_OVERRIDE_GOTO = 252,
3324 #[doc = "Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera."]
3325 MAV_CMD_OBLIQUE_SURVEY = 260,
3326 #[doc = "Enable the specified standard MAVLink mode. If the specified mode is not supported, the vehicle should ACK with MAV_RESULT_FAILED. See <https://mavlink.io/en/services/standard_modes.html>"]
3327 MAV_CMD_DO_SET_STANDARD_MODE = 262,
3328 #[doc = "start running a mission"]
3329 MAV_CMD_MISSION_START = 300,
3330 #[doc = "Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots must NACK this command with MAV_RESULT_TEMPORARILY_REJECTED while armed."]
3331 MAV_CMD_ACTUATOR_TEST = 310,
3332 #[doc = "Actuator configuration command."]
3333 MAV_CMD_CONFIGURE_ACTUATOR = 311,
3334 #[doc = "Arms / Disarms a component"]
3335 MAV_CMD_COMPONENT_ARM_DISARM = 400,
3336 #[doc = "Instructs a target system to run pre-arm checks. This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed. This command should return MAV_RESULT_ACCEPTED if it will run the checks. The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific). The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed."]
3337 MAV_CMD_RUN_PREARM_CHECKS = 401,
3338 #[doc = "Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
3339 MAV_CMD_ILLUMINATOR_ON_OFF = 405,
3340 #[doc = "Configures illuminator settings. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
3341 MAV_CMD_DO_ILLUMINATOR_CONFIGURE = 406,
3342 #[doc = "Request the home position from the vehicle. \t The vehicle will ACK the command and then emit the HOME_POSITION message."]
3343 MAV_CMD_GET_HOME_POSITION = 410,
3344 #[doc = "Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting."]
3345 MAV_CMD_INJECT_FAILURE = 420,
3346 #[doc = "Starts receiver pairing."]
3347 MAV_CMD_START_RX_PAIR = 500,
3348 #[doc = "Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message."]
3349 MAV_CMD_GET_MESSAGE_INTERVAL = 510,
3350 #[doc = "Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM."]
3351 MAV_CMD_SET_MESSAGE_INTERVAL = 511,
3352 #[doc = "Request the target system(s) emit a single instance of a specified message (i.e. a \"one-shot\" version of MAV_CMD_SET_MESSAGE_INTERVAL)."]
3353 MAV_CMD_REQUEST_MESSAGE = 512,
3354 #[doc = "Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message"]
3355 MAV_CMD_REQUEST_PROTOCOL_VERSION = 519,
3356 #[doc = "Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message"]
3357 MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520,
3358 #[doc = "Request camera information (CAMERA_INFORMATION)."]
3359 MAV_CMD_REQUEST_CAMERA_INFORMATION = 521,
3360 #[doc = "Request camera settings (CAMERA_SETTINGS)."]
3361 MAV_CMD_REQUEST_CAMERA_SETTINGS = 522,
3362 #[doc = "Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage."]
3363 MAV_CMD_REQUEST_STORAGE_INFORMATION = 525,
3364 #[doc = "Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage."]
3365 MAV_CMD_STORAGE_FORMAT = 526,
3366 #[doc = "Request camera capture status (CAMERA_CAPTURE_STATUS)"]
3367 MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS = 527,
3368 #[doc = "Request flight information (FLIGHT_INFORMATION)"]
3369 MAV_CMD_REQUEST_FLIGHT_INFORMATION = 528,
3370 #[doc = "Reset all camera settings to Factory Default"]
3371 MAV_CMD_RESET_CAMERA_SETTINGS = 529,
3372 #[doc = "Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming."]
3373 MAV_CMD_SET_CAMERA_MODE = 530,
3374 #[doc = "Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success)."]
3375 MAV_CMD_SET_CAMERA_ZOOM = 531,
3376 #[doc = "Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success)."]
3377 MAV_CMD_SET_CAMERA_FOCUS = 532,
3378 #[doc = "Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos). There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage. If no flag is set the system should use its default storage. A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED. A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED."]
3379 MAV_CMD_SET_STORAGE_USAGE = 533,
3380 #[doc = "Set camera source. Changes the camera's active sources on cameras with multiple image sensors."]
3381 MAV_CMD_SET_CAMERA_SOURCE = 534,
3382 #[doc = "Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG."]
3383 MAV_CMD_JUMP_TAG = 600,
3384 #[doc = "Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number."]
3385 MAV_CMD_DO_JUMP_TAG = 601,
3386 #[doc = "Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate."]
3387 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000,
3388 #[doc = "Gimbal configuration to set which sysid/compid is in primary and secondary control."]
3389 MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001,
3390 #[doc = "Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
3391 MAV_CMD_IMAGE_START_CAPTURE = 2000,
3392 #[doc = "Stop image capture sequence. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
3393 MAV_CMD_IMAGE_STOP_CAPTURE = 2001,
3394 #[doc = "Re-request a CAMERA_IMAGE_CAPTURED message."]
3395 MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE = 2002,
3396 #[doc = "Enable or disable on-board camera triggering system."]
3397 MAV_CMD_DO_TRIGGER_CONTROL = 2003,
3398 #[doc = "If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking."]
3399 MAV_CMD_CAMERA_TRACK_POINT = 2004,
3400 #[doc = "If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking."]
3401 MAV_CMD_CAMERA_TRACK_RECTANGLE = 2005,
3402 #[doc = "Stops ongoing tracking."]
3403 MAV_CMD_CAMERA_STOP_TRACKING = 2010,
3404 #[doc = "Starts video capture (recording)."]
3405 MAV_CMD_VIDEO_START_CAPTURE = 2500,
3406 #[doc = "Stop the current video capture (recording)."]
3407 MAV_CMD_VIDEO_STOP_CAPTURE = 2501,
3408 #[doc = "Start video streaming"]
3409 MAV_CMD_VIDEO_START_STREAMING = 2502,
3410 #[doc = "Stop the given video stream"]
3411 MAV_CMD_VIDEO_STOP_STREAMING = 2503,
3412 #[doc = "Request video stream information (VIDEO_STREAM_INFORMATION)"]
3413 MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION = 2504,
3414 #[doc = "Request video stream status (VIDEO_STREAM_STATUS)"]
3415 MAV_CMD_REQUEST_VIDEO_STREAM_STATUS = 2505,
3416 #[doc = "Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)"]
3417 MAV_CMD_LOGGING_START = 2510,
3418 #[doc = "Request to stop streaming log data over MAVLink"]
3419 MAV_CMD_LOGGING_STOP = 2511,
3420 MAV_CMD_AIRFRAME_CONFIGURATION = 2520,
3421 #[doc = "Request to start/stop transmitting over the high latency telemetry"]
3422 MAV_CMD_CONTROL_HIGH_LATENCY = 2600,
3423 #[doc = "Create a panorama at the current position"]
3424 MAV_CMD_PANORAMA_CREATE = 2800,
3425 #[doc = "Request VTOL transition"]
3426 MAV_CMD_DO_VTOL_TRANSITION = 3000,
3427 #[doc = "Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. \t\tIf approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds. \t\tIf the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON."]
3428 MAV_CMD_ARM_AUTHORIZATION_REQUEST = 3001,
3429 #[doc = "This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes."]
3430 MAV_CMD_SET_GUIDED_SUBMODE_STANDARD = 4000,
3431 #[doc = "This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position."]
3432 MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE = 4001,
3433 #[doc = "Delay mission state machine until gate has been reached."]
3434 MAV_CMD_CONDITION_GATE = 4501,
3435 #[doc = "Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead."]
3436 MAV_CMD_NAV_FENCE_RETURN_POINT = 5000,
3437 #[doc = "Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
3438 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION = 5001,
3439 #[doc = "Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
3440 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION = 5002,
3441 #[doc = "Circular fence area. The vehicle must stay inside this area."]
3442 MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION = 5003,
3443 #[doc = "Circular fence area. The vehicle must stay outside this area."]
3444 MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION = 5004,
3445 #[doc = "Rally point. You can have multiple rally points defined."]
3446 MAV_CMD_NAV_RALLY_POINT = 5100,
3447 #[doc = "Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages."]
3448 MAV_CMD_UAVCAN_GET_NODE_INFO = 5200,
3449 #[doc = "Change state of safety switch."]
3450 MAV_CMD_DO_SET_SAFETY_SWITCH_STATE = 5300,
3451 #[doc = "Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec."]
3452 MAV_CMD_DO_ADSB_OUT_IDENT = 10001,
3453 #[doc = "Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity."]
3454 MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001,
3455 #[doc = "Control the payload deployment."]
3456 MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002,
3457 #[doc = "Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location."]
3458 MAV_CMD_FIXED_MAG_CAL_YAW = 42006,
3459 #[doc = "Command to operate winch."]
3460 MAV_CMD_DO_WINCH = 42600,
3461 #[doc = "Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link."]
3462 MAV_CMD_EXTERNAL_POSITION_ESTIMATE = 43003,
3463 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3464 MAV_CMD_WAYPOINT_USER_1 = 31000,
3465 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3466 MAV_CMD_WAYPOINT_USER_2 = 31001,
3467 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3468 MAV_CMD_WAYPOINT_USER_3 = 31002,
3469 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3470 MAV_CMD_WAYPOINT_USER_4 = 31003,
3471 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
3472 MAV_CMD_WAYPOINT_USER_5 = 31004,
3473 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3474 MAV_CMD_SPATIAL_USER_1 = 31005,
3475 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3476 MAV_CMD_SPATIAL_USER_2 = 31006,
3477 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3478 MAV_CMD_SPATIAL_USER_3 = 31007,
3479 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3480 MAV_CMD_SPATIAL_USER_4 = 31008,
3481 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
3482 MAV_CMD_SPATIAL_USER_5 = 31009,
3483 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3484 MAV_CMD_USER_1 = 31010,
3485 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3486 MAV_CMD_USER_2 = 31011,
3487 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3488 MAV_CMD_USER_3 = 31012,
3489 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3490 MAV_CMD_USER_4 = 31013,
3491 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
3492 MAV_CMD_USER_5 = 31014,
3493 #[doc = "Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages"]
3494 MAV_CMD_CAN_FORWARD = 32000,
3495}
3496impl MavCmd {
3497 pub const DEFAULT: Self = Self::MAV_CMD_NAV_WAYPOINT;
3498}
3499impl Default for MavCmd {
3500 fn default() -> Self {
3501 Self::DEFAULT
3502 }
3503}
3504bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags encode the MAV mode."] pub struct MavModeFlag : u8 { # [doc = "0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state."] const MAV_MODE_FLAG_SAFETY_ARMED = 128 ; # [doc = "0b01000000 remote control input is enabled."] const MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 ; # [doc = "0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational."] const MAV_MODE_FLAG_HIL_ENABLED = 32 ; # [doc = "0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around."] const MAV_MODE_FLAG_STABILIZE_ENABLED = 16 ; # [doc = "0b00001000 guided mode enabled, system flies waypoints / mission items."] const MAV_MODE_FLAG_GUIDED_ENABLED = 8 ; # [doc = "0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation."] const MAV_MODE_FLAG_AUTO_ENABLED = 4 ; # [doc = "0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations."] const MAV_MODE_FLAG_TEST_ENABLED = 2 ; # [doc = "0b00000001 Reserved for future use."] const MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 ; } }
3505impl MavModeFlag {
3506 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_SAFETY_ARMED;
3507}
3508impl Default for MavModeFlag {
3509 fn default() -> Self {
3510 Self::DEFAULT
3511 }
3512}
3513bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) error flags (bitmap, 0 means no error)"] pub struct GimbalDeviceErrorFlags : u32 { # [doc = "Gimbal device is limited by hardware roll limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = 1 ; # [doc = "Gimbal device is limited by hardware pitch limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = 2 ; # [doc = "Gimbal device is limited by hardware yaw limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = 4 ; # [doc = "There is an error with the gimbal encoders."] const GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = 8 ; # [doc = "There is an error with the gimbal power source."] const GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = 16 ; # [doc = "There is an error with the gimbal motors."] const GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = 32 ; # [doc = "There is an error with the gimbal's software."] const GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = 64 ; # [doc = "There is an error with the gimbal's communication."] const GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = 128 ; # [doc = "Gimbal device is currently calibrating."] const GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = 256 ; # [doc = "Gimbal device is not assigned to a gimbal manager."] const GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER = 512 ; } }
3514impl GimbalDeviceErrorFlags {
3515 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT;
3516}
3517impl Default for GimbalDeviceErrorFlags {
3518 fn default() -> Self {
3519 Self::DEFAULT
3520 }
3521}
3522#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3523#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3524#[cfg_attr(feature = "serde", serde(tag = "type"))]
3525#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3526#[repr(u32)]
3527#[doc = "Micro air vehicle / autopilot classes. This identifies the individual model."]
3528pub enum MavAutopilot {
3529 #[doc = "Generic autopilot, full support for everything"]
3530 MAV_AUTOPILOT_GENERIC = 0,
3531 #[doc = "Reserved for future use."]
3532 MAV_AUTOPILOT_RESERVED = 1,
3533 #[doc = "SLUGS autopilot, <http://slugsuav.soe.ucsc.edu>"]
3534 MAV_AUTOPILOT_SLUGS = 2,
3535 #[doc = "ArduPilot - Plane/Copter/Rover/Sub/Tracker, <https://ardupilot.org>"]
3536 MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
3537 #[doc = "OpenPilot, <http://openpilot.org>"]
3538 MAV_AUTOPILOT_OPENPILOT = 4,
3539 #[doc = "Generic autopilot only supporting simple waypoints"]
3540 MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5,
3541 #[doc = "Generic autopilot supporting waypoints and other simple navigation commands"]
3542 MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6,
3543 #[doc = "Generic autopilot supporting the full mission command set"]
3544 MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7,
3545 #[doc = "No valid autopilot, e.g. a GCS or other MAVLink component"]
3546 MAV_AUTOPILOT_INVALID = 8,
3547 #[doc = "PPZ UAV - <http://nongnu.org/paparazzi>"]
3548 MAV_AUTOPILOT_PPZ = 9,
3549 #[doc = "UAV Dev Board"]
3550 MAV_AUTOPILOT_UDB = 10,
3551 #[doc = "FlexiPilot"]
3552 MAV_AUTOPILOT_FP = 11,
3553 #[doc = "PX4 Autopilot - <http://px4.io/>"]
3554 MAV_AUTOPILOT_PX4 = 12,
3555 #[doc = "SMACCMPilot - <http://smaccmpilot.org>"]
3556 MAV_AUTOPILOT_SMACCMPILOT = 13,
3557 #[doc = "AutoQuad -- <http://autoquad.org>"]
3558 MAV_AUTOPILOT_AUTOQUAD = 14,
3559 #[doc = "Armazila -- <http://armazila.com>"]
3560 MAV_AUTOPILOT_ARMAZILA = 15,
3561 #[doc = "Aerob -- <http://aerob.ru>"]
3562 MAV_AUTOPILOT_AEROB = 16,
3563 #[doc = "ASLUAV autopilot -- <http://www.asl.ethz.ch>"]
3564 MAV_AUTOPILOT_ASLUAV = 17,
3565 #[doc = "SmartAP Autopilot - <http://sky-drones.com>"]
3566 MAV_AUTOPILOT_SMARTAP = 18,
3567 #[doc = "AirRails - <http://uaventure.com>"]
3568 MAV_AUTOPILOT_AIRRAILS = 19,
3569 #[doc = "Fusion Reflex - <https://fusion.engineering>"]
3570 MAV_AUTOPILOT_REFLEX = 20,
3571}
3572impl MavAutopilot {
3573 pub const DEFAULT: Self = Self::MAV_AUTOPILOT_GENERIC;
3574}
3575impl Default for MavAutopilot {
3576 fn default() -> Self {
3577 Self::DEFAULT
3578 }
3579}
3580#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3581#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3582#[cfg_attr(feature = "serde", serde(tag = "type"))]
3583#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3584#[repr(u32)]
3585#[doc = "Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
3586pub enum PreflightStorageParameterAction {
3587 #[doc = "Read all parameters from persistent storage. Replaces values in volatile storage."]
3588 PARAM_READ_PERSISTENT = 0,
3589 #[doc = "Write all parameter values to persistent storage (flash/EEPROM)"]
3590 PARAM_WRITE_PERSISTENT = 1,
3591 #[doc = "Reset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics."]
3592 PARAM_RESET_CONFIG_DEFAULT = 2,
3593 #[doc = "Reset only sensor calibration parameters to factory defaults (or firmware default if not available)"]
3594 PARAM_RESET_SENSOR_DEFAULT = 3,
3595 #[doc = "Reset all parameters, including operation counters, to default values"]
3596 PARAM_RESET_ALL_DEFAULT = 4,
3597}
3598impl PreflightStorageParameterAction {
3599 pub const DEFAULT: Self = Self::PARAM_READ_PERSISTENT;
3600}
3601impl Default for PreflightStorageParameterAction {
3602 fn default() -> Self {
3603 Self::DEFAULT
3604 }
3605}
3606#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3607#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3608#[cfg_attr(feature = "serde", serde(tag = "type"))]
3609#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3610#[repr(u32)]
3611#[doc = "Possible actions an aircraft can take to avoid a collision."]
3612pub enum MavCollisionAction {
3613 #[doc = "Ignore any potential collisions"]
3614 MAV_COLLISION_ACTION_NONE = 0,
3615 #[doc = "Report potential collision"]
3616 MAV_COLLISION_ACTION_REPORT = 1,
3617 #[doc = "Ascend or Descend to avoid threat"]
3618 MAV_COLLISION_ACTION_ASCEND_OR_DESCEND = 2,
3619 #[doc = "Move horizontally to avoid threat"]
3620 MAV_COLLISION_ACTION_MOVE_HORIZONTALLY = 3,
3621 #[doc = "Aircraft to move perpendicular to the collision's velocity vector"]
3622 MAV_COLLISION_ACTION_MOVE_PERPENDICULAR = 4,
3623 #[doc = "Aircraft to fly directly back to its launch point"]
3624 MAV_COLLISION_ACTION_RTL = 5,
3625 #[doc = "Aircraft to stop in place"]
3626 MAV_COLLISION_ACTION_HOVER = 6,
3627}
3628impl MavCollisionAction {
3629 pub const DEFAULT: Self = Self::MAV_COLLISION_ACTION_NONE;
3630}
3631impl Default for MavCollisionAction {
3632 fn default() -> Self {
3633 Self::DEFAULT
3634 }
3635}
3636#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3637#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3638#[cfg_attr(feature = "serde", serde(tag = "type"))]
3639#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3640#[repr(u32)]
3641#[doc = "Type of landing target"]
3642pub enum LandingTargetType {
3643 #[doc = "Landing target signaled by light beacon (ex: IR-LOCK)"]
3644 LANDING_TARGET_TYPE_LIGHT_BEACON = 0,
3645 #[doc = "Landing target signaled by radio beacon (ex: ILS, NDB)"]
3646 LANDING_TARGET_TYPE_RADIO_BEACON = 1,
3647 #[doc = "Landing target represented by a fiducial marker (ex: ARTag)"]
3648 LANDING_TARGET_TYPE_VISION_FIDUCIAL = 2,
3649 #[doc = "Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)"]
3650 LANDING_TARGET_TYPE_VISION_OTHER = 3,
3651}
3652impl LandingTargetType {
3653 pub const DEFAULT: Self = Self::LANDING_TARGET_TYPE_LIGHT_BEACON;
3654}
3655impl Default for LandingTargetType {
3656 fn default() -> Self {
3657 Self::DEFAULT
3658 }
3659}
3660#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3661#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3662#[cfg_attr(feature = "serde", serde(tag = "type"))]
3663#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3664#[repr(u32)]
3665#[doc = "Tune formats (used for vehicle buzzer/tone generation)."]
3666pub enum TuneFormat {
3667 #[doc = "Format is QBasic 1.1 Play: <https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm>."]
3668 TUNE_FORMAT_QBASIC1_1 = 1,
3669 #[doc = "Format is Modern Music Markup Language (MML): <https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML>."]
3670 TUNE_FORMAT_MML_MODERN = 2,
3671}
3672impl TuneFormat {
3673 pub const DEFAULT: Self = Self::TUNE_FORMAT_QBASIC1_1;
3674}
3675impl Default for TuneFormat {
3676 fn default() -> Self {
3677 Self::DEFAULT
3678 }
3679}
3680bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Power supply status flags (bitmask)"] pub struct MavPowerStatus : u16 { # [doc = "main brick power supply valid"] const MAV_POWER_STATUS_BRICK_VALID = 1 ; # [doc = "main servo power supply valid for FMU"] const MAV_POWER_STATUS_SERVO_VALID = 2 ; # [doc = "USB power is connected"] const MAV_POWER_STATUS_USB_CONNECTED = 4 ; # [doc = "peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 ; # [doc = "hi-power peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 ; # [doc = "Power status has changed since boot"] const MAV_POWER_STATUS_CHANGED = 32 ; } }
3681impl MavPowerStatus {
3682 pub const DEFAULT: Self = Self::MAV_POWER_STATUS_BRICK_VALID;
3683}
3684impl Default for MavPowerStatus {
3685 fn default() -> Self {
3686 Self::DEFAULT
3687 }
3688}
3689#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3690#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3691#[cfg_attr(feature = "serde", serde(tag = "type"))]
3692#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3693#[repr(u32)]
3694#[doc = "Camera tracking status flags"]
3695pub enum CameraTrackingStatusFlags {
3696 #[doc = "Camera is not tracking"]
3697 CAMERA_TRACKING_STATUS_FLAGS_IDLE = 0,
3698 #[doc = "Camera is tracking"]
3699 CAMERA_TRACKING_STATUS_FLAGS_ACTIVE = 1,
3700 #[doc = "Camera tracking in error state"]
3701 CAMERA_TRACKING_STATUS_FLAGS_ERROR = 2,
3702}
3703impl CameraTrackingStatusFlags {
3704 pub const DEFAULT: Self = Self::CAMERA_TRACKING_STATUS_FLAGS_IDLE;
3705}
3706impl Default for CameraTrackingStatusFlags {
3707 fn default() -> Self {
3708 Self::DEFAULT
3709 }
3710}
3711bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera capability flags (Bitmap)"] pub struct CameraCapFlags : u32 { # [doc = "Camera is able to record video"] const CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 1 ; # [doc = "Camera is able to capture images"] const CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 2 ; # [doc = "Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_MODES = 4 ; # [doc = "Camera can capture images while in video mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = 8 ; # [doc = "Camera can capture videos while in Photo/Image mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = 16 ; # [doc = "Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = 32 ; # [doc = "Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM)"] const CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = 64 ; # [doc = "Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS)"] const CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = 128 ; # [doc = "Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info)"] const CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = 256 ; # [doc = "Camera supports tracking of a point on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = 512 ; # [doc = "Camera supports tracking of a selection rectangle on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = 1024 ; # [doc = "Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS)."] const CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = 2048 ; # [doc = "Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE)."] const CAMERA_CAP_FLAGS_HAS_THERMAL_RANGE = 4096 ; } }
3712impl CameraCapFlags {
3713 pub const DEFAULT: Self = Self::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
3714}
3715impl Default for CameraCapFlags {
3716 fn default() -> Self {
3717 Self::DEFAULT
3718 }
3719}
3720#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3721#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3722#[cfg_attr(feature = "serde", serde(tag = "type"))]
3723#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3724#[repr(u32)]
3725pub enum MavOdidOperatorLocationType {
3726 #[doc = "The location/altitude of the operator is the same as the take-off location."]
3727 MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF = 0,
3728 #[doc = "The location/altitude of the operator is dynamic. E.g. based on live GNSS data."]
3729 MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS = 1,
3730 #[doc = "The location/altitude of the operator are fixed values."]
3731 MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED = 2,
3732}
3733impl MavOdidOperatorLocationType {
3734 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF;
3735}
3736impl Default for MavOdidOperatorLocationType {
3737 fn default() -> Self {
3738 Self::DEFAULT
3739 }
3740}
3741#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3742#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3743#[cfg_attr(feature = "serde", serde(tag = "type"))]
3744#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3745#[repr(u32)]
3746#[doc = "These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not."]
3747pub enum MavModeFlagDecodePosition {
3748 #[doc = "First bit: 10000000"]
3749 MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128,
3750 #[doc = "Second bit: 01000000"]
3751 MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64,
3752 #[doc = "Third bit: 00100000"]
3753 MAV_MODE_FLAG_DECODE_POSITION_HIL = 32,
3754 #[doc = "Fourth bit: 00010000"]
3755 MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16,
3756 #[doc = "Fifth bit: 00001000"]
3757 MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8,
3758 #[doc = "Sixth bit: 00000100"]
3759 MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4,
3760 #[doc = "Seventh bit: 00000010"]
3761 MAV_MODE_FLAG_DECODE_POSITION_TEST = 2,
3762 #[doc = "Eighth bit: 00000001"]
3763 MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1,
3764}
3765impl MavModeFlagDecodePosition {
3766 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
3767}
3768impl Default for MavModeFlagDecodePosition {
3769 fn default() -> Self {
3770 Self::DEFAULT
3771 }
3772}
3773#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3774#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3775#[cfg_attr(feature = "serde", serde(tag = "type"))]
3776#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3777#[repr(u32)]
3778#[doc = "Standard modes with a well understood meaning across flight stacks and vehicle types. For example, most flight stack have the concept of a \"return\" or \"RTL\" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. The modes supported by a flight stack can be queried using AVAILABLE_MODES and set using MAV_CMD_DO_SET_STANDARD_MODE. The current mode is streamed in CURRENT_MODE. See <https://mavlink.io/en/services/standard_modes.html>"]
3779pub enum MavStandardMode {
3780 #[doc = "Non standard mode. This may be used when reporting the mode if the current flight mode is not a standard mode."]
3781 MAV_STANDARD_MODE_NON_STANDARD = 0,
3782 #[doc = "Position mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. This mode can only be set by vehicles that can hold a fixed position. Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. Fixed-wing (FW) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
3783 MAV_STANDARD_MODE_POSITION_HOLD = 1,
3784 #[doc = "Orbit (manual). Position-controlled and stabilized manual mode. The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. Flight stacks may support the [MAV_CMD_DO_ORBIT](<https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT>) for changing the orbit parameters. MC and FW vehicles may support this mode. Hybrid MC/FW (\"VTOL\") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
3785 MAV_STANDARD_MODE_ORBIT = 2,
3786 #[doc = "Cruise mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. Multicopter (MC) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
3787 MAV_STANDARD_MODE_CRUISE = 3,
3788 #[doc = "Altitude hold (manual). Altitude-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their altitude. MC vehicles continue with existing momentum and may move with wind (or other external forces). FW vehicles continue with current heading, but may be moved off-track by wind. Hybrid MC/FW (\"VTOL\") vehicles behave according to their current configuration/mode (FW or MC). Other vehicle types must not support this mode (this may be revisited through the PR process)."]
3789 MAV_STANDARD_MODE_ALTITUDE_HOLD = 4,
3790 #[doc = "Safe recovery mode (auto). Automatic mode that takes vehicle to a predefined safe location via a safe flight path, and may also automatically land the vehicle. This mode is more commonly referred to as RTL and/or or Smart RTL. The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. For example, the vehicle might return to the home/launch location, a rally point, or the start of a mission landing, it might follow a direct path, mission path, or breadcrumb path, and land using a mission landing pattern or some other kind of descent."]
3791 MAV_STANDARD_MODE_SAFE_RECOVERY = 5,
3792 #[doc = "Mission mode (automatic). Automatic mode that executes MAVLink missions. Missions are executed from the current waypoint as soon as the mode is enabled."]
3793 MAV_STANDARD_MODE_MISSION = 6,
3794 #[doc = "Land mode (auto). Automatic mode that lands the vehicle at the current location. The precise landing behaviour depends on vehicle configuration and type."]
3795 MAV_STANDARD_MODE_LAND = 7,
3796 #[doc = "Takeoff mode (auto). Automatic takeoff mode. The precise takeoff behaviour depends on vehicle configuration and type."]
3797 MAV_STANDARD_MODE_TAKEOFF = 8,
3798}
3799impl MavStandardMode {
3800 pub const DEFAULT: Self = Self::MAV_STANDARD_MODE_NON_STANDARD;
3801}
3802impl Default for MavStandardMode {
3803 fn default() -> Self {
3804 Self::DEFAULT
3805 }
3806}
3807#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3808#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3809#[cfg_attr(feature = "serde", serde(tag = "type"))]
3810#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3811#[repr(u32)]
3812#[doc = "Enumeration of sensor orientation, according to its rotations"]
3813pub enum MavSensorOrientation {
3814 #[doc = "Roll: 0, Pitch: 0, Yaw: 0"]
3815 MAV_SENSOR_ROTATION_NONE = 0,
3816 #[doc = "Roll: 0, Pitch: 0, Yaw: 45"]
3817 MAV_SENSOR_ROTATION_YAW_45 = 1,
3818 #[doc = "Roll: 0, Pitch: 0, Yaw: 90"]
3819 MAV_SENSOR_ROTATION_YAW_90 = 2,
3820 #[doc = "Roll: 0, Pitch: 0, Yaw: 135"]
3821 MAV_SENSOR_ROTATION_YAW_135 = 3,
3822 #[doc = "Roll: 0, Pitch: 0, Yaw: 180"]
3823 MAV_SENSOR_ROTATION_YAW_180 = 4,
3824 #[doc = "Roll: 0, Pitch: 0, Yaw: 225"]
3825 MAV_SENSOR_ROTATION_YAW_225 = 5,
3826 #[doc = "Roll: 0, Pitch: 0, Yaw: 270"]
3827 MAV_SENSOR_ROTATION_YAW_270 = 6,
3828 #[doc = "Roll: 0, Pitch: 0, Yaw: 315"]
3829 MAV_SENSOR_ROTATION_YAW_315 = 7,
3830 #[doc = "Roll: 180, Pitch: 0, Yaw: 0"]
3831 MAV_SENSOR_ROTATION_ROLL_180 = 8,
3832 #[doc = "Roll: 180, Pitch: 0, Yaw: 45"]
3833 MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9,
3834 #[doc = "Roll: 180, Pitch: 0, Yaw: 90"]
3835 MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10,
3836 #[doc = "Roll: 180, Pitch: 0, Yaw: 135"]
3837 MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11,
3838 #[doc = "Roll: 0, Pitch: 180, Yaw: 0"]
3839 MAV_SENSOR_ROTATION_PITCH_180 = 12,
3840 #[doc = "Roll: 180, Pitch: 0, Yaw: 225"]
3841 MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13,
3842 #[doc = "Roll: 180, Pitch: 0, Yaw: 270"]
3843 MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14,
3844 #[doc = "Roll: 180, Pitch: 0, Yaw: 315"]
3845 MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15,
3846 #[doc = "Roll: 90, Pitch: 0, Yaw: 0"]
3847 MAV_SENSOR_ROTATION_ROLL_90 = 16,
3848 #[doc = "Roll: 90, Pitch: 0, Yaw: 45"]
3849 MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17,
3850 #[doc = "Roll: 90, Pitch: 0, Yaw: 90"]
3851 MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18,
3852 #[doc = "Roll: 90, Pitch: 0, Yaw: 135"]
3853 MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19,
3854 #[doc = "Roll: 270, Pitch: 0, Yaw: 0"]
3855 MAV_SENSOR_ROTATION_ROLL_270 = 20,
3856 #[doc = "Roll: 270, Pitch: 0, Yaw: 45"]
3857 MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21,
3858 #[doc = "Roll: 270, Pitch: 0, Yaw: 90"]
3859 MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22,
3860 #[doc = "Roll: 270, Pitch: 0, Yaw: 135"]
3861 MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23,
3862 #[doc = "Roll: 0, Pitch: 90, Yaw: 0"]
3863 MAV_SENSOR_ROTATION_PITCH_90 = 24,
3864 #[doc = "Roll: 0, Pitch: 270, Yaw: 0"]
3865 MAV_SENSOR_ROTATION_PITCH_270 = 25,
3866 #[doc = "Roll: 0, Pitch: 180, Yaw: 90"]
3867 MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26,
3868 #[doc = "Roll: 0, Pitch: 180, Yaw: 270"]
3869 MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27,
3870 #[doc = "Roll: 90, Pitch: 90, Yaw: 0"]
3871 MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28,
3872 #[doc = "Roll: 180, Pitch: 90, Yaw: 0"]
3873 MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29,
3874 #[doc = "Roll: 270, Pitch: 90, Yaw: 0"]
3875 MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30,
3876 #[doc = "Roll: 90, Pitch: 180, Yaw: 0"]
3877 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31,
3878 #[doc = "Roll: 270, Pitch: 180, Yaw: 0"]
3879 MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32,
3880 #[doc = "Roll: 90, Pitch: 270, Yaw: 0"]
3881 MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33,
3882 #[doc = "Roll: 180, Pitch: 270, Yaw: 0"]
3883 MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34,
3884 #[doc = "Roll: 270, Pitch: 270, Yaw: 0"]
3885 MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35,
3886 #[doc = "Roll: 90, Pitch: 180, Yaw: 90"]
3887 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
3888 #[doc = "Roll: 90, Pitch: 0, Yaw: 270"]
3889 MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37,
3890 #[doc = "Roll: 90, Pitch: 68, Yaw: 293"]
3891 MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
3892 #[doc = "Pitch: 315"]
3893 MAV_SENSOR_ROTATION_PITCH_315 = 39,
3894 #[doc = "Roll: 90, Pitch: 315"]
3895 MAV_SENSOR_ROTATION_ROLL_90_PITCH_315 = 40,
3896 #[doc = "Custom orientation"]
3897 MAV_SENSOR_ROTATION_CUSTOM = 100,
3898}
3899impl MavSensorOrientation {
3900 pub const DEFAULT: Self = Self::MAV_SENSOR_ROTATION_NONE;
3901}
3902impl Default for MavSensorOrientation {
3903 fn default() -> Self {
3904 Self::DEFAULT
3905 }
3906}
3907bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields."] pub struct MavSysStatusSensorExtended : u32 { # [doc = "0x01 Recovery system (parachute, balloon, retracts etc)"] const MAV_SYS_STATUS_RECOVERY_SYSTEM = 1 ; } }
3908impl MavSysStatusSensorExtended {
3909 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_RECOVERY_SYSTEM;
3910}
3911impl Default for MavSysStatusSensorExtended {
3912 fn default() -> Self {
3913 Self::DEFAULT
3914 }
3915}
3916#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3917#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3918#[cfg_attr(feature = "serde", serde(tag = "type"))]
3919#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3920#[repr(u32)]
3921pub enum FenceBreach {
3922 #[doc = "No last fence breach"]
3923 FENCE_BREACH_NONE = 0,
3924 #[doc = "Breached minimum altitude"]
3925 FENCE_BREACH_MINALT = 1,
3926 #[doc = "Breached maximum altitude"]
3927 FENCE_BREACH_MAXALT = 2,
3928 #[doc = "Breached fence boundary"]
3929 FENCE_BREACH_BOUNDARY = 3,
3930}
3931impl FenceBreach {
3932 pub const DEFAULT: Self = Self::FENCE_BREACH_NONE;
3933}
3934impl Default for FenceBreach {
3935 fn default() -> Self {
3936 Self::DEFAULT
3937 }
3938}
3939bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Stream status flags (Bitmap)"] pub struct VideoStreamStatusFlags : u16 { # [doc = "Stream is active (running)"] const VIDEO_STREAM_STATUS_FLAGS_RUNNING = 1 ; # [doc = "Stream is thermal imaging"] const VIDEO_STREAM_STATUS_FLAGS_THERMAL = 2 ; # [doc = "Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE)."] const VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED = 4 ; } }
3940impl VideoStreamStatusFlags {
3941 pub const DEFAULT: Self = Self::VIDEO_STREAM_STATUS_FLAGS_RUNNING;
3942}
3943impl Default for VideoStreamStatusFlags {
3944 fn default() -> Self {
3945 Self::DEFAULT
3946 }
3947}
3948#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3949#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3950#[cfg_attr(feature = "serde", serde(tag = "type"))]
3951#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3952#[repr(u32)]
3953pub enum MavOdidCategoryEu {
3954 #[doc = "The category for the UA, according to the EU specification, is undeclared."]
3955 MAV_ODID_CATEGORY_EU_UNDECLARED = 0,
3956 #[doc = "The category for the UA, according to the EU specification, is the Open category."]
3957 MAV_ODID_CATEGORY_EU_OPEN = 1,
3958 #[doc = "The category for the UA, according to the EU specification, is the Specific category."]
3959 MAV_ODID_CATEGORY_EU_SPECIFIC = 2,
3960 #[doc = "The category for the UA, according to the EU specification, is the Certified category."]
3961 MAV_ODID_CATEGORY_EU_CERTIFIED = 3,
3962}
3963impl MavOdidCategoryEu {
3964 pub const DEFAULT: Self = Self::MAV_ODID_CATEGORY_EU_UNDECLARED;
3965}
3966impl Default for MavOdidCategoryEu {
3967 fn default() -> Self {
3968 Self::DEFAULT
3969 }
3970}
3971#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3972#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3973#[cfg_attr(feature = "serde", serde(tag = "type"))]
3974#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3975#[repr(u32)]
3976#[doc = "Enumeration of distance sensor types"]
3977pub enum MavDistanceSensor {
3978 #[doc = "Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units"]
3979 MAV_DISTANCE_SENSOR_LASER = 0,
3980 #[doc = "Ultrasound rangefinder, e.g. MaxBotix units"]
3981 MAV_DISTANCE_SENSOR_ULTRASOUND = 1,
3982 #[doc = "Infrared rangefinder, e.g. Sharp units"]
3983 MAV_DISTANCE_SENSOR_INFRARED = 2,
3984 #[doc = "Radar type, e.g. uLanding units"]
3985 MAV_DISTANCE_SENSOR_RADAR = 3,
3986 #[doc = "Broken or unknown type, e.g. analog units"]
3987 MAV_DISTANCE_SENSOR_UNKNOWN = 4,
3988}
3989impl MavDistanceSensor {
3990 pub const DEFAULT: Self = Self::MAV_DISTANCE_SENSOR_LASER;
3991}
3992impl Default for MavDistanceSensor {
3993 fn default() -> Self {
3994 Self::DEFAULT
3995 }
3996}
3997#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3998#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3999#[cfg_attr(feature = "serde", serde(tag = "type"))]
4000#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4001#[repr(u32)]
4002#[doc = "Specifies the datatype of a MAVLink extended parameter."]
4003pub enum MavParamExtType {
4004 #[doc = "8-bit unsigned integer"]
4005 MAV_PARAM_EXT_TYPE_UINT8 = 1,
4006 #[doc = "8-bit signed integer"]
4007 MAV_PARAM_EXT_TYPE_INT8 = 2,
4008 #[doc = "16-bit unsigned integer"]
4009 MAV_PARAM_EXT_TYPE_UINT16 = 3,
4010 #[doc = "16-bit signed integer"]
4011 MAV_PARAM_EXT_TYPE_INT16 = 4,
4012 #[doc = "32-bit unsigned integer"]
4013 MAV_PARAM_EXT_TYPE_UINT32 = 5,
4014 #[doc = "32-bit signed integer"]
4015 MAV_PARAM_EXT_TYPE_INT32 = 6,
4016 #[doc = "64-bit unsigned integer"]
4017 MAV_PARAM_EXT_TYPE_UINT64 = 7,
4018 #[doc = "64-bit signed integer"]
4019 MAV_PARAM_EXT_TYPE_INT64 = 8,
4020 #[doc = "32-bit floating-point"]
4021 MAV_PARAM_EXT_TYPE_REAL32 = 9,
4022 #[doc = "64-bit floating-point"]
4023 MAV_PARAM_EXT_TYPE_REAL64 = 10,
4024 #[doc = "Custom Type"]
4025 MAV_PARAM_EXT_TYPE_CUSTOM = 11,
4026}
4027impl MavParamExtType {
4028 pub const DEFAULT: Self = Self::MAV_PARAM_EXT_TYPE_UINT8;
4029}
4030impl Default for MavParamExtType {
4031 fn default() -> Self {
4032 Self::DEFAULT
4033 }
4034}
4035bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored."] pub struct AttitudeTargetTypemask : u8 { # [doc = "Ignore body roll rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = 1 ; # [doc = "Ignore body pitch rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = 2 ; # [doc = "Ignore body yaw rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = 4 ; # [doc = "Use 3D body thrust setpoint instead of throttle"] const ATTITUDE_TARGET_TYPEMASK_THRUST_BODY_SET = 32 ; # [doc = "Ignore throttle"] const ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = 64 ; # [doc = "Ignore attitude"] const ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = 128 ; } }
4036impl AttitudeTargetTypemask {
4037 pub const DEFAULT: Self = Self::ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE;
4038}
4039impl Default for AttitudeTargetTypemask {
4040 fn default() -> Self {
4041 Self::DEFAULT
4042 }
4043}
4044#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4045#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4046#[cfg_attr(feature = "serde", serde(tag = "type"))]
4047#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4048#[repr(u32)]
4049#[doc = "List of possible failure type to inject."]
4050pub enum FailureType {
4051 #[doc = "No failure injected, used to reset a previous failure."]
4052 FAILURE_TYPE_OK = 0,
4053 #[doc = "Sets unit off, so completely non-responsive."]
4054 FAILURE_TYPE_OFF = 1,
4055 #[doc = "Unit is stuck e.g. keeps reporting the same value."]
4056 FAILURE_TYPE_STUCK = 2,
4057 #[doc = "Unit is reporting complete garbage."]
4058 FAILURE_TYPE_GARBAGE = 3,
4059 #[doc = "Unit is consistently wrong."]
4060 FAILURE_TYPE_WRONG = 4,
4061 #[doc = "Unit is slow, so e.g. reporting at slower than expected rate."]
4062 FAILURE_TYPE_SLOW = 5,
4063 #[doc = "Data of unit is delayed in time."]
4064 FAILURE_TYPE_DELAYED = 6,
4065 #[doc = "Unit is sometimes working, sometimes not."]
4066 FAILURE_TYPE_INTERMITTENT = 7,
4067}
4068impl FailureType {
4069 pub const DEFAULT: Self = Self::FAILURE_TYPE_OK;
4070}
4071impl Default for FailureType {
4072 fn default() -> Self {
4073 Self::DEFAULT
4074 }
4075}
4076#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4077#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4078#[cfg_attr(feature = "serde", serde(tag = "type"))]
4079#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4080#[repr(u32)]
4081#[doc = "Enumeration of estimator types"]
4082pub enum MavEstimatorType {
4083 #[doc = "Unknown type of the estimator."]
4084 MAV_ESTIMATOR_TYPE_UNKNOWN = 0,
4085 #[doc = "This is a naive estimator without any real covariance feedback."]
4086 MAV_ESTIMATOR_TYPE_NAIVE = 1,
4087 #[doc = "Computer vision based estimate. Might be up to scale."]
4088 MAV_ESTIMATOR_TYPE_VISION = 2,
4089 #[doc = "Visual-inertial estimate."]
4090 MAV_ESTIMATOR_TYPE_VIO = 3,
4091 #[doc = "Plain GPS estimate."]
4092 MAV_ESTIMATOR_TYPE_GPS = 4,
4093 #[doc = "Estimator integrating GPS and inertial sensing."]
4094 MAV_ESTIMATOR_TYPE_GPS_INS = 5,
4095 #[doc = "Estimate from external motion capturing system."]
4096 MAV_ESTIMATOR_TYPE_MOCAP = 6,
4097 #[doc = "Estimator based on lidar sensor input."]
4098 MAV_ESTIMATOR_TYPE_LIDAR = 7,
4099 #[doc = "Estimator on autopilot."]
4100 MAV_ESTIMATOR_TYPE_AUTOPILOT = 8,
4101}
4102impl MavEstimatorType {
4103 pub const DEFAULT: Self = Self::MAV_ESTIMATOR_TYPE_UNKNOWN;
4104}
4105impl Default for MavEstimatorType {
4106 fn default() -> Self {
4107 Self::DEFAULT
4108 }
4109}
4110#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4111#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4112#[cfg_attr(feature = "serde", serde(tag = "type"))]
4113#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4114#[repr(u32)]
4115#[doc = "Camera Modes."]
4116pub enum CameraMode {
4117 #[doc = "Camera is in image/photo capture mode."]
4118 CAMERA_MODE_IMAGE = 0,
4119 #[doc = "Camera is in video capture mode."]
4120 CAMERA_MODE_VIDEO = 1,
4121 #[doc = "Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys."]
4122 CAMERA_MODE_IMAGE_SURVEY = 2,
4123}
4124impl CameraMode {
4125 pub const DEFAULT: Self = Self::CAMERA_MODE_IMAGE;
4126}
4127impl Default for CameraMode {
4128 fn default() -> Self {
4129 Self::DEFAULT
4130 }
4131}
4132#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4133#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4134#[cfg_attr(feature = "serde", serde(tag = "type"))]
4135#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4136#[repr(u32)]
4137#[doc = "Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST."]
4138pub enum MotorTestThrottleType {
4139 #[doc = "Throttle as a percentage (0 ~ 100)"]
4140 MOTOR_TEST_THROTTLE_PERCENT = 0,
4141 #[doc = "Throttle as an absolute PWM value (normally in range of 1000~2000)."]
4142 MOTOR_TEST_THROTTLE_PWM = 1,
4143 #[doc = "Throttle pass-through from pilot's transmitter."]
4144 MOTOR_TEST_THROTTLE_PILOT = 2,
4145 #[doc = "Per-motor compass calibration test."]
4146 MOTOR_TEST_COMPASS_CAL = 3,
4147}
4148impl MotorTestThrottleType {
4149 pub const DEFAULT: Self = Self::MOTOR_TEST_THROTTLE_PERCENT;
4150}
4151impl Default for MotorTestThrottleType {
4152 fn default() -> Self {
4153 Self::DEFAULT
4154 }
4155}
4156bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set."] pub struct MavBatteryFault : u32 { # [doc = "Battery has deep discharged."] const MAV_BATTERY_FAULT_DEEP_DISCHARGE = 1 ; # [doc = "Voltage spikes."] const MAV_BATTERY_FAULT_SPIKES = 2 ; # [doc = "One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used)."] const MAV_BATTERY_FAULT_CELL_FAIL = 4 ; # [doc = "Over-current fault."] const MAV_BATTERY_FAULT_OVER_CURRENT = 8 ; # [doc = "Over-temperature fault."] const MAV_BATTERY_FAULT_OVER_TEMPERATURE = 16 ; # [doc = "Under-temperature fault."] const MAV_BATTERY_FAULT_UNDER_TEMPERATURE = 32 ; # [doc = "Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)."] const MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 64 ; # [doc = "Battery firmware is not compatible with current autopilot firmware."] const MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 128 ; # [doc = "Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s)."] const BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION = 256 ; } }
4157impl MavBatteryFault {
4158 pub const DEFAULT: Self = Self::MAV_BATTERY_FAULT_DEEP_DISCHARGE;
4159}
4160impl Default for MavBatteryFault {
4161 fn default() -> Self {
4162 Self::DEFAULT
4163 }
4164}
4165#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4166#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4167#[cfg_attr(feature = "serde", serde(tag = "type"))]
4168#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4169#[repr(u32)]
4170#[doc = "Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution."]
4171pub enum MavGoto {
4172 #[doc = "Hold at the current position."]
4173 MAV_GOTO_DO_HOLD = 0,
4174 #[doc = "Continue with the next item in mission execution."]
4175 MAV_GOTO_DO_CONTINUE = 1,
4176 #[doc = "Hold at the current position of the system"]
4177 MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2,
4178 #[doc = "Hold at the position specified in the parameters of the DO_HOLD action"]
4179 MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3,
4180}
4181impl MavGoto {
4182 pub const DEFAULT: Self = Self::MAV_GOTO_DO_HOLD;
4183}
4184impl Default for MavGoto {
4185 fn default() -> Self {
4186 Self::DEFAULT
4187 }
4188}
4189#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4190#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4191#[cfg_attr(feature = "serde", serde(tag = "type"))]
4192#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4193#[repr(u32)]
4194#[doc = "Enumeration for battery charge states."]
4195pub enum MavBatteryChargeState {
4196 #[doc = "Low battery state is not provided"]
4197 MAV_BATTERY_CHARGE_STATE_UNDEFINED = 0,
4198 #[doc = "Battery is not in low state. Normal operation."]
4199 MAV_BATTERY_CHARGE_STATE_OK = 1,
4200 #[doc = "Battery state is low, warn and monitor close."]
4201 MAV_BATTERY_CHARGE_STATE_LOW = 2,
4202 #[doc = "Battery state is critical, return or abort immediately."]
4203 MAV_BATTERY_CHARGE_STATE_CRITICAL = 3,
4204 #[doc = "Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage."]
4205 MAV_BATTERY_CHARGE_STATE_EMERGENCY = 4,
4206 #[doc = "Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
4207 MAV_BATTERY_CHARGE_STATE_FAILED = 5,
4208 #[doc = "Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
4209 MAV_BATTERY_CHARGE_STATE_UNHEALTHY = 6,
4210 #[doc = "Battery is charging."]
4211 MAV_BATTERY_CHARGE_STATE_CHARGING = 7,
4212}
4213impl MavBatteryChargeState {
4214 pub const DEFAULT: Self = Self::MAV_BATTERY_CHARGE_STATE_UNDEFINED;
4215}
4216impl Default for MavBatteryChargeState {
4217 fn default() -> Self {
4218 Self::DEFAULT
4219 }
4220}
4221bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Winch status flags used in WINCH_STATUS"] pub struct MavWinchStatusFlag : u32 { # [doc = "Winch is healthy"] const MAV_WINCH_STATUS_HEALTHY = 1 ; # [doc = "Winch line is fully retracted"] const MAV_WINCH_STATUS_FULLY_RETRACTED = 2 ; # [doc = "Winch motor is moving"] const MAV_WINCH_STATUS_MOVING = 4 ; # [doc = "Winch clutch is engaged allowing motor to move freely."] const MAV_WINCH_STATUS_CLUTCH_ENGAGED = 8 ; # [doc = "Winch is locked by locking mechanism."] const MAV_WINCH_STATUS_LOCKED = 16 ; # [doc = "Winch is gravity dropping payload."] const MAV_WINCH_STATUS_DROPPING = 32 ; # [doc = "Winch is arresting payload descent."] const MAV_WINCH_STATUS_ARRESTING = 64 ; # [doc = "Winch is using torque measurements to sense the ground."] const MAV_WINCH_STATUS_GROUND_SENSE = 128 ; # [doc = "Winch is returning to the fully retracted position."] const MAV_WINCH_STATUS_RETRACTING = 256 ; # [doc = "Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING."] const MAV_WINCH_STATUS_REDELIVER = 512 ; # [doc = "Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold."] const MAV_WINCH_STATUS_ABANDON_LINE = 1024 ; # [doc = "Winch is engaging the locking mechanism."] const MAV_WINCH_STATUS_LOCKING = 2048 ; # [doc = "Winch is spooling on line."] const MAV_WINCH_STATUS_LOAD_LINE = 4096 ; # [doc = "Winch is loading a payload."] const MAV_WINCH_STATUS_LOAD_PAYLOAD = 8192 ; } }
4222impl MavWinchStatusFlag {
4223 pub const DEFAULT: Self = Self::MAV_WINCH_STATUS_HEALTHY;
4224}
4225impl Default for MavWinchStatusFlag {
4226 fn default() -> Self {
4227 Self::DEFAULT
4228 }
4229}
4230#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4231#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4232#[cfg_attr(feature = "serde", serde(tag = "type"))]
4233#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4234#[repr(u32)]
4235#[doc = "Axes that will be autotuned by MAV_CMD_DO_AUTOTUNE_ENABLE. Note that at least one flag must be set in MAV_CMD_DO_AUTOTUNE_ENABLE.param2: if none are set, the flight stack will tune its default set of axes."]
4236pub enum AutotuneAxis {
4237 #[doc = "Autotune roll axis."]
4238 AUTOTUNE_AXIS_ROLL = 1,
4239 #[doc = "Autotune pitch axis."]
4240 AUTOTUNE_AXIS_PITCH = 2,
4241 #[doc = "Autotune yaw axis."]
4242 AUTOTUNE_AXIS_YAW = 4,
4243}
4244impl AutotuneAxis {
4245 pub const DEFAULT: Self = Self::AUTOTUNE_AXIS_ROLL;
4246}
4247impl Default for AutotuneAxis {
4248 fn default() -> Self {
4249 Self::DEFAULT
4250 }
4251}
4252bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera tracking target data (shows where tracked target is within image)"] pub struct CameraTrackingTargetData : u8 { # [doc = "Target data embedded in image data (proprietary)"] const CAMERA_TRACKING_TARGET_DATA_EMBEDDED = 1 ; # [doc = "Target data rendered in image"] const CAMERA_TRACKING_TARGET_DATA_RENDERED = 2 ; # [doc = "Target data within status message (Point or Rectangle)"] const CAMERA_TRACKING_TARGET_DATA_IN_STATUS = 4 ; } }
4253impl CameraTrackingTargetData {
4254 pub const DEFAULT: Self = Self::CAMERA_TRACKING_TARGET_DATA_EMBEDDED;
4255}
4256impl Default for CameraTrackingTargetData {
4257 fn default() -> Self {
4258 Self::DEFAULT
4259 }
4260}
4261#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4262#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4263#[cfg_attr(feature = "serde", serde(tag = "type"))]
4264#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4265#[repr(u32)]
4266#[doc = "Generalized UAVCAN node health"]
4267pub enum UavcanNodeHealth {
4268 #[doc = "The node is functioning properly."]
4269 UAVCAN_NODE_HEALTH_OK = 0,
4270 #[doc = "A critical parameter went out of range or the node has encountered a minor failure."]
4271 UAVCAN_NODE_HEALTH_WARNING = 1,
4272 #[doc = "The node has encountered a major failure."]
4273 UAVCAN_NODE_HEALTH_ERROR = 2,
4274 #[doc = "The node has suffered a fatal malfunction."]
4275 UAVCAN_NODE_HEALTH_CRITICAL = 3,
4276}
4277impl UavcanNodeHealth {
4278 pub const DEFAULT: Self = Self::UAVCAN_NODE_HEALTH_OK;
4279}
4280impl Default for UavcanNodeHealth {
4281 fn default() -> Self {
4282 Self::DEFAULT
4283 }
4284}
4285bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags indicate status such as data validity of each data source. Set = data valid"] pub struct AdsbFlags : u16 { const ADSB_FLAGS_VALID_COORDS = 1 ; const ADSB_FLAGS_VALID_ALTITUDE = 2 ; const ADSB_FLAGS_VALID_HEADING = 4 ; const ADSB_FLAGS_VALID_VELOCITY = 8 ; const ADSB_FLAGS_VALID_CALLSIGN = 16 ; const ADSB_FLAGS_VALID_SQUAWK = 32 ; const ADSB_FLAGS_SIMULATED = 64 ; const ADSB_FLAGS_VERTICAL_VELOCITY_VALID = 128 ; const ADSB_FLAGS_BARO_VALID = 256 ; const ADSB_FLAGS_SOURCE_UAT = 32768 ; } }
4286impl AdsbFlags {
4287 pub const DEFAULT: Self = Self::ADSB_FLAGS_VALID_COORDS;
4288}
4289impl Default for AdsbFlags {
4290 fn default() -> Self {
4291 Self::DEFAULT
4292 }
4293}
4294#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4295#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4296#[cfg_attr(feature = "serde", serde(tag = "type"))]
4297#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4298#[repr(u32)]
4299#[doc = "Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED"]
4300pub enum SpeedType {
4301 #[doc = "Airspeed"]
4302 SPEED_TYPE_AIRSPEED = 0,
4303 #[doc = "Groundspeed"]
4304 SPEED_TYPE_GROUNDSPEED = 1,
4305 #[doc = "Climb speed"]
4306 SPEED_TYPE_CLIMB_SPEED = 2,
4307 #[doc = "Descent speed"]
4308 SPEED_TYPE_DESCENT_SPEED = 3,
4309}
4310impl SpeedType {
4311 pub const DEFAULT: Self = Self::SPEED_TYPE_AIRSPEED;
4312}
4313impl Default for SpeedType {
4314 fn default() -> Self {
4315 Self::DEFAULT
4316 }
4317}
4318#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4319#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4320#[cfg_attr(feature = "serde", serde(tag = "type"))]
4321#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4322#[repr(u32)]
4323#[doc = "The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI)."]
4324pub enum MavRoi {
4325 #[doc = "No region of interest."]
4326 MAV_ROI_NONE = 0,
4327 #[doc = "Point toward next waypoint, with optional pitch/roll/yaw offset."]
4328 MAV_ROI_WPNEXT = 1,
4329 #[doc = "Point toward given waypoint."]
4330 MAV_ROI_WPINDEX = 2,
4331 #[doc = "Point toward fixed location."]
4332 MAV_ROI_LOCATION = 3,
4333 #[doc = "Point toward of given id."]
4334 MAV_ROI_TARGET = 4,
4335}
4336impl MavRoi {
4337 pub const DEFAULT: Self = Self::MAV_ROI_NONE;
4338}
4339impl Default for MavRoi {
4340 fn default() -> Self {
4341 Self::DEFAULT
4342 }
4343}
4344#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4345#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4346#[cfg_attr(feature = "serde", serde(tag = "type"))]
4347#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4348#[repr(u32)]
4349#[doc = "Result from PARAM_EXT_SET message."]
4350pub enum ParamAck {
4351 #[doc = "Parameter value ACCEPTED and SET"]
4352 PARAM_ACK_ACCEPTED = 0,
4353 #[doc = "Parameter value UNKNOWN/UNSUPPORTED"]
4354 PARAM_ACK_VALUE_UNSUPPORTED = 1,
4355 #[doc = "Parameter failed to set"]
4356 PARAM_ACK_FAILED = 2,
4357 #[doc = "Parameter value received but not yet set/accepted. A subsequent PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent."]
4358 PARAM_ACK_IN_PROGRESS = 3,
4359}
4360impl ParamAck {
4361 pub const DEFAULT: Self = Self::PARAM_ACK_ACCEPTED;
4362}
4363impl Default for ParamAck {
4364 fn default() -> Self {
4365 Self::DEFAULT
4366 }
4367}
4368#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4369#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4370#[cfg_attr(feature = "serde", serde(tag = "type"))]
4371#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4372#[repr(u32)]
4373#[doc = "Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: <http://www.kiwisyslog.com/kb/info:-syslog-message-levels/>."]
4374pub enum MavSeverity {
4375 #[doc = "System is unusable. This is a \"panic\" condition."]
4376 MAV_SEVERITY_EMERGENCY = 0,
4377 #[doc = "Action should be taken immediately. Indicates error in non-critical systems."]
4378 MAV_SEVERITY_ALERT = 1,
4379 #[doc = "Action must be taken immediately. Indicates failure in a primary system."]
4380 MAV_SEVERITY_CRITICAL = 2,
4381 #[doc = "Indicates an error in secondary/redundant systems."]
4382 MAV_SEVERITY_ERROR = 3,
4383 #[doc = "Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning."]
4384 MAV_SEVERITY_WARNING = 4,
4385 #[doc = "An unusual event has occurred, though not an error condition. This should be investigated for the root cause."]
4386 MAV_SEVERITY_NOTICE = 5,
4387 #[doc = "Normal operational messages. Useful for logging. No action is required for these messages."]
4388 MAV_SEVERITY_INFO = 6,
4389 #[doc = "Useful non-operational messages that can assist in debugging. These should not occur during normal operation."]
4390 MAV_SEVERITY_DEBUG = 7,
4391}
4392impl MavSeverity {
4393 pub const DEFAULT: Self = Self::MAV_SEVERITY_EMERGENCY;
4394}
4395impl Default for MavSeverity {
4396 fn default() -> Self {
4397 Self::DEFAULT
4398 }
4399}
4400#[doc = "id: 69"]
4401#[doc = "This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask."]
4402#[derive(Debug, Clone, PartialEq)]
4403#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4404#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4405pub struct MANUAL_CONTROL_DATA {
4406 #[doc = "X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle."]
4407 pub x: i16,
4408 #[doc = "Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle."]
4409 pub y: i16,
4410 #[doc = "Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust."]
4411 pub z: i16,
4412 #[doc = "R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle."]
4413 pub r: i16,
4414 #[doc = "A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1."]
4415 pub buttons: u16,
4416 #[doc = "The system to be controlled."]
4417 pub target: u8,
4418 #[doc = "A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16."]
4419 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4420 pub buttons2: u16,
4421 #[doc = "Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6"]
4422 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4423 pub enabled_extensions: u8,
4424 #[doc = "Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid."]
4425 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4426 pub s: i16,
4427 #[doc = "Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid."]
4428 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4429 pub t: i16,
4430 #[doc = "Aux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset."]
4431 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4432 pub aux1: i16,
4433 #[doc = "Aux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset."]
4434 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4435 pub aux2: i16,
4436 #[doc = "Aux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset."]
4437 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4438 pub aux3: i16,
4439 #[doc = "Aux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset."]
4440 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4441 pub aux4: i16,
4442 #[doc = "Aux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset."]
4443 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4444 pub aux5: i16,
4445 #[doc = "Aux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset."]
4446 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4447 pub aux6: i16,
4448}
4449impl MANUAL_CONTROL_DATA {
4450 pub const ENCODED_LEN: usize = 30usize;
4451 pub const DEFAULT: Self = Self {
4452 x: 0_i16,
4453 y: 0_i16,
4454 z: 0_i16,
4455 r: 0_i16,
4456 buttons: 0_u16,
4457 target: 0_u8,
4458 buttons2: 0_u16,
4459 enabled_extensions: 0_u8,
4460 s: 0_i16,
4461 t: 0_i16,
4462 aux1: 0_i16,
4463 aux2: 0_i16,
4464 aux3: 0_i16,
4465 aux4: 0_i16,
4466 aux5: 0_i16,
4467 aux6: 0_i16,
4468 };
4469 #[cfg(feature = "arbitrary")]
4470 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4471 use arbitrary::{Arbitrary, Unstructured};
4472 let mut buf = [0u8; 1024];
4473 rng.fill_bytes(&mut buf);
4474 let mut unstructured = Unstructured::new(&buf);
4475 Self::arbitrary(&mut unstructured).unwrap_or_default()
4476 }
4477}
4478impl Default for MANUAL_CONTROL_DATA {
4479 fn default() -> Self {
4480 Self::DEFAULT.clone()
4481 }
4482}
4483impl MessageData for MANUAL_CONTROL_DATA {
4484 type Message = MavMessage;
4485 const ID: u32 = 69u32;
4486 const NAME: &'static str = "MANUAL_CONTROL";
4487 const EXTRA_CRC: u8 = 243u8;
4488 const ENCODED_LEN: usize = 30usize;
4489 fn deser(
4490 _version: MavlinkVersion,
4491 __input: &[u8],
4492 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4493 let avail_len = __input.len();
4494 let mut payload_buf = [0; Self::ENCODED_LEN];
4495 let mut buf = if avail_len < Self::ENCODED_LEN {
4496 payload_buf[0..avail_len].copy_from_slice(__input);
4497 Bytes::new(&payload_buf)
4498 } else {
4499 Bytes::new(__input)
4500 };
4501 let mut __struct = Self::default();
4502 __struct.x = buf.get_i16_le();
4503 __struct.y = buf.get_i16_le();
4504 __struct.z = buf.get_i16_le();
4505 __struct.r = buf.get_i16_le();
4506 __struct.buttons = buf.get_u16_le();
4507 __struct.target = buf.get_u8();
4508 __struct.buttons2 = buf.get_u16_le();
4509 __struct.enabled_extensions = buf.get_u8();
4510 __struct.s = buf.get_i16_le();
4511 __struct.t = buf.get_i16_le();
4512 __struct.aux1 = buf.get_i16_le();
4513 __struct.aux2 = buf.get_i16_le();
4514 __struct.aux3 = buf.get_i16_le();
4515 __struct.aux4 = buf.get_i16_le();
4516 __struct.aux5 = buf.get_i16_le();
4517 __struct.aux6 = buf.get_i16_le();
4518 Ok(__struct)
4519 }
4520 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4521 let mut __tmp = BytesMut::new(bytes);
4522 #[allow(clippy::absurd_extreme_comparisons)]
4523 #[allow(unused_comparisons)]
4524 if __tmp.remaining() < Self::ENCODED_LEN {
4525 panic!(
4526 "buffer is too small (need {} bytes, but got {})",
4527 Self::ENCODED_LEN,
4528 __tmp.remaining(),
4529 )
4530 }
4531 __tmp.put_i16_le(self.x);
4532 __tmp.put_i16_le(self.y);
4533 __tmp.put_i16_le(self.z);
4534 __tmp.put_i16_le(self.r);
4535 __tmp.put_u16_le(self.buttons);
4536 __tmp.put_u8(self.target);
4537 __tmp.put_u16_le(self.buttons2);
4538 __tmp.put_u8(self.enabled_extensions);
4539 __tmp.put_i16_le(self.s);
4540 __tmp.put_i16_le(self.t);
4541 __tmp.put_i16_le(self.aux1);
4542 __tmp.put_i16_le(self.aux2);
4543 __tmp.put_i16_le(self.aux3);
4544 __tmp.put_i16_le(self.aux4);
4545 __tmp.put_i16_le(self.aux5);
4546 __tmp.put_i16_le(self.aux6);
4547 if matches!(version, MavlinkVersion::V2) {
4548 let len = __tmp.len();
4549 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4550 } else {
4551 __tmp.len()
4552 }
4553 }
4554}
4555#[doc = "id: 248"]
4556#[doc = "Message implementing parts of the V2 payload specs in V1 frames for transitional support."]
4557#[derive(Debug, Clone, PartialEq)]
4558#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4559#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4560pub struct V2_EXTENSION_DATA {
4561 #[doc = "A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to <https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml>. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
4562 pub message_type: u16,
4563 #[doc = "Network ID (0 for broadcast)"]
4564 pub target_network: u8,
4565 #[doc = "System ID (0 for broadcast)"]
4566 pub target_system: u8,
4567 #[doc = "Component ID (0 for broadcast)"]
4568 pub target_component: u8,
4569 #[doc = "Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification."]
4570 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4571 pub payload: [u8; 249],
4572}
4573impl V2_EXTENSION_DATA {
4574 pub const ENCODED_LEN: usize = 254usize;
4575 pub const DEFAULT: Self = Self {
4576 message_type: 0_u16,
4577 target_network: 0_u8,
4578 target_system: 0_u8,
4579 target_component: 0_u8,
4580 payload: [0_u8; 249usize],
4581 };
4582 #[cfg(feature = "arbitrary")]
4583 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4584 use arbitrary::{Arbitrary, Unstructured};
4585 let mut buf = [0u8; 1024];
4586 rng.fill_bytes(&mut buf);
4587 let mut unstructured = Unstructured::new(&buf);
4588 Self::arbitrary(&mut unstructured).unwrap_or_default()
4589 }
4590}
4591impl Default for V2_EXTENSION_DATA {
4592 fn default() -> Self {
4593 Self::DEFAULT.clone()
4594 }
4595}
4596impl MessageData for V2_EXTENSION_DATA {
4597 type Message = MavMessage;
4598 const ID: u32 = 248u32;
4599 const NAME: &'static str = "V2_EXTENSION";
4600 const EXTRA_CRC: u8 = 8u8;
4601 const ENCODED_LEN: usize = 254usize;
4602 fn deser(
4603 _version: MavlinkVersion,
4604 __input: &[u8],
4605 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4606 let avail_len = __input.len();
4607 let mut payload_buf = [0; Self::ENCODED_LEN];
4608 let mut buf = if avail_len < Self::ENCODED_LEN {
4609 payload_buf[0..avail_len].copy_from_slice(__input);
4610 Bytes::new(&payload_buf)
4611 } else {
4612 Bytes::new(__input)
4613 };
4614 let mut __struct = Self::default();
4615 __struct.message_type = buf.get_u16_le();
4616 __struct.target_network = buf.get_u8();
4617 __struct.target_system = buf.get_u8();
4618 __struct.target_component = buf.get_u8();
4619 for v in &mut __struct.payload {
4620 let val = buf.get_u8();
4621 *v = val;
4622 }
4623 Ok(__struct)
4624 }
4625 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4626 let mut __tmp = BytesMut::new(bytes);
4627 #[allow(clippy::absurd_extreme_comparisons)]
4628 #[allow(unused_comparisons)]
4629 if __tmp.remaining() < Self::ENCODED_LEN {
4630 panic!(
4631 "buffer is too small (need {} bytes, but got {})",
4632 Self::ENCODED_LEN,
4633 __tmp.remaining(),
4634 )
4635 }
4636 __tmp.put_u16_le(self.message_type);
4637 __tmp.put_u8(self.target_network);
4638 __tmp.put_u8(self.target_system);
4639 __tmp.put_u8(self.target_component);
4640 for val in &self.payload {
4641 __tmp.put_u8(*val);
4642 }
4643 if matches!(version, MavlinkVersion::V2) {
4644 let len = __tmp.len();
4645 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4646 } else {
4647 __tmp.len()
4648 }
4649 }
4650}
4651#[doc = "id: 101"]
4652#[doc = "Global position/attitude estimate from a vision source."]
4653#[derive(Debug, Clone, PartialEq)]
4654#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4655#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4656pub struct GLOBAL_VISION_POSITION_ESTIMATE_DATA {
4657 #[doc = "Timestamp (UNIX time or since system boot)"]
4658 pub usec: u64,
4659 #[doc = "Global X position"]
4660 pub x: f32,
4661 #[doc = "Global Y position"]
4662 pub y: f32,
4663 #[doc = "Global Z position"]
4664 pub z: f32,
4665 #[doc = "Roll angle"]
4666 pub roll: f32,
4667 #[doc = "Pitch angle"]
4668 pub pitch: f32,
4669 #[doc = "Yaw angle"]
4670 pub yaw: f32,
4671 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
4672 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4673 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
4674 pub covariance: [f32; 21],
4675 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
4676 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4677 pub reset_counter: u8,
4678}
4679impl GLOBAL_VISION_POSITION_ESTIMATE_DATA {
4680 pub const ENCODED_LEN: usize = 117usize;
4681 pub const DEFAULT: Self = Self {
4682 usec: 0_u64,
4683 x: 0.0_f32,
4684 y: 0.0_f32,
4685 z: 0.0_f32,
4686 roll: 0.0_f32,
4687 pitch: 0.0_f32,
4688 yaw: 0.0_f32,
4689 covariance: [0.0_f32; 21usize],
4690 reset_counter: 0_u8,
4691 };
4692 #[cfg(feature = "arbitrary")]
4693 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4694 use arbitrary::{Arbitrary, Unstructured};
4695 let mut buf = [0u8; 1024];
4696 rng.fill_bytes(&mut buf);
4697 let mut unstructured = Unstructured::new(&buf);
4698 Self::arbitrary(&mut unstructured).unwrap_or_default()
4699 }
4700}
4701impl Default for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
4702 fn default() -> Self {
4703 Self::DEFAULT.clone()
4704 }
4705}
4706impl MessageData for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
4707 type Message = MavMessage;
4708 const ID: u32 = 101u32;
4709 const NAME: &'static str = "GLOBAL_VISION_POSITION_ESTIMATE";
4710 const EXTRA_CRC: u8 = 102u8;
4711 const ENCODED_LEN: usize = 117usize;
4712 fn deser(
4713 _version: MavlinkVersion,
4714 __input: &[u8],
4715 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4716 let avail_len = __input.len();
4717 let mut payload_buf = [0; Self::ENCODED_LEN];
4718 let mut buf = if avail_len < Self::ENCODED_LEN {
4719 payload_buf[0..avail_len].copy_from_slice(__input);
4720 Bytes::new(&payload_buf)
4721 } else {
4722 Bytes::new(__input)
4723 };
4724 let mut __struct = Self::default();
4725 __struct.usec = buf.get_u64_le();
4726 __struct.x = buf.get_f32_le();
4727 __struct.y = buf.get_f32_le();
4728 __struct.z = buf.get_f32_le();
4729 __struct.roll = buf.get_f32_le();
4730 __struct.pitch = buf.get_f32_le();
4731 __struct.yaw = buf.get_f32_le();
4732 for v in &mut __struct.covariance {
4733 let val = buf.get_f32_le();
4734 *v = val;
4735 }
4736 __struct.reset_counter = buf.get_u8();
4737 Ok(__struct)
4738 }
4739 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4740 let mut __tmp = BytesMut::new(bytes);
4741 #[allow(clippy::absurd_extreme_comparisons)]
4742 #[allow(unused_comparisons)]
4743 if __tmp.remaining() < Self::ENCODED_LEN {
4744 panic!(
4745 "buffer is too small (need {} bytes, but got {})",
4746 Self::ENCODED_LEN,
4747 __tmp.remaining(),
4748 )
4749 }
4750 __tmp.put_u64_le(self.usec);
4751 __tmp.put_f32_le(self.x);
4752 __tmp.put_f32_le(self.y);
4753 __tmp.put_f32_le(self.z);
4754 __tmp.put_f32_le(self.roll);
4755 __tmp.put_f32_le(self.pitch);
4756 __tmp.put_f32_le(self.yaw);
4757 for val in &self.covariance {
4758 __tmp.put_f32_le(*val);
4759 }
4760 __tmp.put_u8(self.reset_counter);
4761 if matches!(version, MavlinkVersion::V2) {
4762 let len = __tmp.len();
4763 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4764 } else {
4765 __tmp.len()
4766 }
4767 }
4768}
4769#[doc = "id: 100"]
4770#[doc = "Optical flow from a flow sensor (e.g. optical mouse sensor)."]
4771#[derive(Debug, Clone, PartialEq)]
4772#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4773#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4774pub struct OPTICAL_FLOW_DATA {
4775 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
4776 pub time_usec: u64,
4777 #[doc = "Flow in x-sensor direction, angular-speed compensated"]
4778 pub flow_comp_m_x: f32,
4779 #[doc = "Flow in y-sensor direction, angular-speed compensated"]
4780 pub flow_comp_m_y: f32,
4781 #[doc = "Ground distance. Positive value: distance known. Negative value: Unknown distance"]
4782 pub ground_distance: f32,
4783 #[doc = "Flow in x-sensor direction"]
4784 pub flow_x: i16,
4785 #[doc = "Flow in y-sensor direction"]
4786 pub flow_y: i16,
4787 #[doc = "Sensor ID"]
4788 pub sensor_id: u8,
4789 #[doc = "Optical flow quality / confidence. 0: bad, 255: maximum quality"]
4790 pub quality: u8,
4791 #[doc = "Flow rate about X axis"]
4792 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4793 pub flow_rate_x: f32,
4794 #[doc = "Flow rate about Y axis"]
4795 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4796 pub flow_rate_y: f32,
4797}
4798impl OPTICAL_FLOW_DATA {
4799 pub const ENCODED_LEN: usize = 34usize;
4800 pub const DEFAULT: Self = Self {
4801 time_usec: 0_u64,
4802 flow_comp_m_x: 0.0_f32,
4803 flow_comp_m_y: 0.0_f32,
4804 ground_distance: 0.0_f32,
4805 flow_x: 0_i16,
4806 flow_y: 0_i16,
4807 sensor_id: 0_u8,
4808 quality: 0_u8,
4809 flow_rate_x: 0.0_f32,
4810 flow_rate_y: 0.0_f32,
4811 };
4812 #[cfg(feature = "arbitrary")]
4813 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4814 use arbitrary::{Arbitrary, Unstructured};
4815 let mut buf = [0u8; 1024];
4816 rng.fill_bytes(&mut buf);
4817 let mut unstructured = Unstructured::new(&buf);
4818 Self::arbitrary(&mut unstructured).unwrap_or_default()
4819 }
4820}
4821impl Default for OPTICAL_FLOW_DATA {
4822 fn default() -> Self {
4823 Self::DEFAULT.clone()
4824 }
4825}
4826impl MessageData for OPTICAL_FLOW_DATA {
4827 type Message = MavMessage;
4828 const ID: u32 = 100u32;
4829 const NAME: &'static str = "OPTICAL_FLOW";
4830 const EXTRA_CRC: u8 = 175u8;
4831 const ENCODED_LEN: usize = 34usize;
4832 fn deser(
4833 _version: MavlinkVersion,
4834 __input: &[u8],
4835 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4836 let avail_len = __input.len();
4837 let mut payload_buf = [0; Self::ENCODED_LEN];
4838 let mut buf = if avail_len < Self::ENCODED_LEN {
4839 payload_buf[0..avail_len].copy_from_slice(__input);
4840 Bytes::new(&payload_buf)
4841 } else {
4842 Bytes::new(__input)
4843 };
4844 let mut __struct = Self::default();
4845 __struct.time_usec = buf.get_u64_le();
4846 __struct.flow_comp_m_x = buf.get_f32_le();
4847 __struct.flow_comp_m_y = buf.get_f32_le();
4848 __struct.ground_distance = buf.get_f32_le();
4849 __struct.flow_x = buf.get_i16_le();
4850 __struct.flow_y = buf.get_i16_le();
4851 __struct.sensor_id = buf.get_u8();
4852 __struct.quality = buf.get_u8();
4853 __struct.flow_rate_x = buf.get_f32_le();
4854 __struct.flow_rate_y = buf.get_f32_le();
4855 Ok(__struct)
4856 }
4857 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4858 let mut __tmp = BytesMut::new(bytes);
4859 #[allow(clippy::absurd_extreme_comparisons)]
4860 #[allow(unused_comparisons)]
4861 if __tmp.remaining() < Self::ENCODED_LEN {
4862 panic!(
4863 "buffer is too small (need {} bytes, but got {})",
4864 Self::ENCODED_LEN,
4865 __tmp.remaining(),
4866 )
4867 }
4868 __tmp.put_u64_le(self.time_usec);
4869 __tmp.put_f32_le(self.flow_comp_m_x);
4870 __tmp.put_f32_le(self.flow_comp_m_y);
4871 __tmp.put_f32_le(self.ground_distance);
4872 __tmp.put_i16_le(self.flow_x);
4873 __tmp.put_i16_le(self.flow_y);
4874 __tmp.put_u8(self.sensor_id);
4875 __tmp.put_u8(self.quality);
4876 __tmp.put_f32_le(self.flow_rate_x);
4877 __tmp.put_f32_le(self.flow_rate_y);
4878 if matches!(version, MavlinkVersion::V2) {
4879 let len = __tmp.len();
4880 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4881 } else {
4882 __tmp.len()
4883 }
4884 }
4885}
4886#[doc = "id: 380"]
4887#[doc = "Time/duration estimates for various events and actions given the current vehicle state and position."]
4888#[derive(Debug, Clone, PartialEq)]
4889#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4890#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4891pub struct TIME_ESTIMATE_TO_TARGET_DATA {
4892 #[doc = "Estimated time to complete the vehicle's configured \"safe return\" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available."]
4893 pub safe_return: i32,
4894 #[doc = "Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available."]
4895 pub land: i32,
4896 #[doc = "Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available."]
4897 pub mission_next_item: i32,
4898 #[doc = "Estimated time for completing the current mission. -1 means no mission active and/or no estimate available."]
4899 pub mission_end: i32,
4900 #[doc = "Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available."]
4901 pub commanded_action: i32,
4902}
4903impl TIME_ESTIMATE_TO_TARGET_DATA {
4904 pub const ENCODED_LEN: usize = 20usize;
4905 pub const DEFAULT: Self = Self {
4906 safe_return: 0_i32,
4907 land: 0_i32,
4908 mission_next_item: 0_i32,
4909 mission_end: 0_i32,
4910 commanded_action: 0_i32,
4911 };
4912 #[cfg(feature = "arbitrary")]
4913 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4914 use arbitrary::{Arbitrary, Unstructured};
4915 let mut buf = [0u8; 1024];
4916 rng.fill_bytes(&mut buf);
4917 let mut unstructured = Unstructured::new(&buf);
4918 Self::arbitrary(&mut unstructured).unwrap_or_default()
4919 }
4920}
4921impl Default for TIME_ESTIMATE_TO_TARGET_DATA {
4922 fn default() -> Self {
4923 Self::DEFAULT.clone()
4924 }
4925}
4926impl MessageData for TIME_ESTIMATE_TO_TARGET_DATA {
4927 type Message = MavMessage;
4928 const ID: u32 = 380u32;
4929 const NAME: &'static str = "TIME_ESTIMATE_TO_TARGET";
4930 const EXTRA_CRC: u8 = 232u8;
4931 const ENCODED_LEN: usize = 20usize;
4932 fn deser(
4933 _version: MavlinkVersion,
4934 __input: &[u8],
4935 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4936 let avail_len = __input.len();
4937 let mut payload_buf = [0; Self::ENCODED_LEN];
4938 let mut buf = if avail_len < Self::ENCODED_LEN {
4939 payload_buf[0..avail_len].copy_from_slice(__input);
4940 Bytes::new(&payload_buf)
4941 } else {
4942 Bytes::new(__input)
4943 };
4944 let mut __struct = Self::default();
4945 __struct.safe_return = buf.get_i32_le();
4946 __struct.land = buf.get_i32_le();
4947 __struct.mission_next_item = buf.get_i32_le();
4948 __struct.mission_end = buf.get_i32_le();
4949 __struct.commanded_action = buf.get_i32_le();
4950 Ok(__struct)
4951 }
4952 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4953 let mut __tmp = BytesMut::new(bytes);
4954 #[allow(clippy::absurd_extreme_comparisons)]
4955 #[allow(unused_comparisons)]
4956 if __tmp.remaining() < Self::ENCODED_LEN {
4957 panic!(
4958 "buffer is too small (need {} bytes, but got {})",
4959 Self::ENCODED_LEN,
4960 __tmp.remaining(),
4961 )
4962 }
4963 __tmp.put_i32_le(self.safe_return);
4964 __tmp.put_i32_le(self.land);
4965 __tmp.put_i32_le(self.mission_next_item);
4966 __tmp.put_i32_le(self.mission_end);
4967 __tmp.put_i32_le(self.commanded_action);
4968 if matches!(version, MavlinkVersion::V2) {
4969 let len = __tmp.len();
4970 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4971 } else {
4972 __tmp.len()
4973 }
4974 }
4975}
4976#[doc = "id: 92"]
4977#[doc = "Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification."]
4978#[derive(Debug, Clone, PartialEq)]
4979#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4980#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4981pub struct HIL_RC_INPUTS_RAW_DATA {
4982 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
4983 pub time_usec: u64,
4984 #[doc = "RC channel 1 value"]
4985 pub chan1_raw: u16,
4986 #[doc = "RC channel 2 value"]
4987 pub chan2_raw: u16,
4988 #[doc = "RC channel 3 value"]
4989 pub chan3_raw: u16,
4990 #[doc = "RC channel 4 value"]
4991 pub chan4_raw: u16,
4992 #[doc = "RC channel 5 value"]
4993 pub chan5_raw: u16,
4994 #[doc = "RC channel 6 value"]
4995 pub chan6_raw: u16,
4996 #[doc = "RC channel 7 value"]
4997 pub chan7_raw: u16,
4998 #[doc = "RC channel 8 value"]
4999 pub chan8_raw: u16,
5000 #[doc = "RC channel 9 value"]
5001 pub chan9_raw: u16,
5002 #[doc = "RC channel 10 value"]
5003 pub chan10_raw: u16,
5004 #[doc = "RC channel 11 value"]
5005 pub chan11_raw: u16,
5006 #[doc = "RC channel 12 value"]
5007 pub chan12_raw: u16,
5008 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
5009 pub rssi: u8,
5010}
5011impl HIL_RC_INPUTS_RAW_DATA {
5012 pub const ENCODED_LEN: usize = 33usize;
5013 pub const DEFAULT: Self = Self {
5014 time_usec: 0_u64,
5015 chan1_raw: 0_u16,
5016 chan2_raw: 0_u16,
5017 chan3_raw: 0_u16,
5018 chan4_raw: 0_u16,
5019 chan5_raw: 0_u16,
5020 chan6_raw: 0_u16,
5021 chan7_raw: 0_u16,
5022 chan8_raw: 0_u16,
5023 chan9_raw: 0_u16,
5024 chan10_raw: 0_u16,
5025 chan11_raw: 0_u16,
5026 chan12_raw: 0_u16,
5027 rssi: 0_u8,
5028 };
5029 #[cfg(feature = "arbitrary")]
5030 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5031 use arbitrary::{Arbitrary, Unstructured};
5032 let mut buf = [0u8; 1024];
5033 rng.fill_bytes(&mut buf);
5034 let mut unstructured = Unstructured::new(&buf);
5035 Self::arbitrary(&mut unstructured).unwrap_or_default()
5036 }
5037}
5038impl Default for HIL_RC_INPUTS_RAW_DATA {
5039 fn default() -> Self {
5040 Self::DEFAULT.clone()
5041 }
5042}
5043impl MessageData for HIL_RC_INPUTS_RAW_DATA {
5044 type Message = MavMessage;
5045 const ID: u32 = 92u32;
5046 const NAME: &'static str = "HIL_RC_INPUTS_RAW";
5047 const EXTRA_CRC: u8 = 54u8;
5048 const ENCODED_LEN: usize = 33usize;
5049 fn deser(
5050 _version: MavlinkVersion,
5051 __input: &[u8],
5052 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5053 let avail_len = __input.len();
5054 let mut payload_buf = [0; Self::ENCODED_LEN];
5055 let mut buf = if avail_len < Self::ENCODED_LEN {
5056 payload_buf[0..avail_len].copy_from_slice(__input);
5057 Bytes::new(&payload_buf)
5058 } else {
5059 Bytes::new(__input)
5060 };
5061 let mut __struct = Self::default();
5062 __struct.time_usec = buf.get_u64_le();
5063 __struct.chan1_raw = buf.get_u16_le();
5064 __struct.chan2_raw = buf.get_u16_le();
5065 __struct.chan3_raw = buf.get_u16_le();
5066 __struct.chan4_raw = buf.get_u16_le();
5067 __struct.chan5_raw = buf.get_u16_le();
5068 __struct.chan6_raw = buf.get_u16_le();
5069 __struct.chan7_raw = buf.get_u16_le();
5070 __struct.chan8_raw = buf.get_u16_le();
5071 __struct.chan9_raw = buf.get_u16_le();
5072 __struct.chan10_raw = buf.get_u16_le();
5073 __struct.chan11_raw = buf.get_u16_le();
5074 __struct.chan12_raw = buf.get_u16_le();
5075 __struct.rssi = buf.get_u8();
5076 Ok(__struct)
5077 }
5078 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5079 let mut __tmp = BytesMut::new(bytes);
5080 #[allow(clippy::absurd_extreme_comparisons)]
5081 #[allow(unused_comparisons)]
5082 if __tmp.remaining() < Self::ENCODED_LEN {
5083 panic!(
5084 "buffer is too small (need {} bytes, but got {})",
5085 Self::ENCODED_LEN,
5086 __tmp.remaining(),
5087 )
5088 }
5089 __tmp.put_u64_le(self.time_usec);
5090 __tmp.put_u16_le(self.chan1_raw);
5091 __tmp.put_u16_le(self.chan2_raw);
5092 __tmp.put_u16_le(self.chan3_raw);
5093 __tmp.put_u16_le(self.chan4_raw);
5094 __tmp.put_u16_le(self.chan5_raw);
5095 __tmp.put_u16_le(self.chan6_raw);
5096 __tmp.put_u16_le(self.chan7_raw);
5097 __tmp.put_u16_le(self.chan8_raw);
5098 __tmp.put_u16_le(self.chan9_raw);
5099 __tmp.put_u16_le(self.chan10_raw);
5100 __tmp.put_u16_le(self.chan11_raw);
5101 __tmp.put_u16_le(self.chan12_raw);
5102 __tmp.put_u8(self.rssi);
5103 if matches!(version, MavlinkVersion::V2) {
5104 let len = __tmp.len();
5105 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5106 } else {
5107 __tmp.len()
5108 }
5109 }
5110}
5111#[doc = "id: 12915"]
5112#[doc = "An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon."]
5113#[derive(Debug, Clone, PartialEq)]
5114#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5115#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5116pub struct OPEN_DRONE_ID_MESSAGE_PACK_DATA {
5117 #[doc = "System ID (0 for broadcast)."]
5118 pub target_system: u8,
5119 #[doc = "Component ID (0 for broadcast)."]
5120 pub target_component: u8,
5121 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
5122 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5123 pub id_or_mac: [u8; 20],
5124 #[doc = "This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length."]
5125 pub single_message_size: u8,
5126 #[doc = "Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9."]
5127 pub msg_pack_size: u8,
5128 #[doc = "Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field."]
5129 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5130 pub messages: [u8; 225],
5131}
5132impl OPEN_DRONE_ID_MESSAGE_PACK_DATA {
5133 pub const ENCODED_LEN: usize = 249usize;
5134 pub const DEFAULT: Self = Self {
5135 target_system: 0_u8,
5136 target_component: 0_u8,
5137 id_or_mac: [0_u8; 20usize],
5138 single_message_size: 0_u8,
5139 msg_pack_size: 0_u8,
5140 messages: [0_u8; 225usize],
5141 };
5142 #[cfg(feature = "arbitrary")]
5143 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5144 use arbitrary::{Arbitrary, Unstructured};
5145 let mut buf = [0u8; 1024];
5146 rng.fill_bytes(&mut buf);
5147 let mut unstructured = Unstructured::new(&buf);
5148 Self::arbitrary(&mut unstructured).unwrap_or_default()
5149 }
5150}
5151impl Default for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
5152 fn default() -> Self {
5153 Self::DEFAULT.clone()
5154 }
5155}
5156impl MessageData for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
5157 type Message = MavMessage;
5158 const ID: u32 = 12915u32;
5159 const NAME: &'static str = "OPEN_DRONE_ID_MESSAGE_PACK";
5160 const EXTRA_CRC: u8 = 94u8;
5161 const ENCODED_LEN: usize = 249usize;
5162 fn deser(
5163 _version: MavlinkVersion,
5164 __input: &[u8],
5165 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5166 let avail_len = __input.len();
5167 let mut payload_buf = [0; Self::ENCODED_LEN];
5168 let mut buf = if avail_len < Self::ENCODED_LEN {
5169 payload_buf[0..avail_len].copy_from_slice(__input);
5170 Bytes::new(&payload_buf)
5171 } else {
5172 Bytes::new(__input)
5173 };
5174 let mut __struct = Self::default();
5175 __struct.target_system = buf.get_u8();
5176 __struct.target_component = buf.get_u8();
5177 for v in &mut __struct.id_or_mac {
5178 let val = buf.get_u8();
5179 *v = val;
5180 }
5181 __struct.single_message_size = buf.get_u8();
5182 __struct.msg_pack_size = buf.get_u8();
5183 for v in &mut __struct.messages {
5184 let val = buf.get_u8();
5185 *v = val;
5186 }
5187 Ok(__struct)
5188 }
5189 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5190 let mut __tmp = BytesMut::new(bytes);
5191 #[allow(clippy::absurd_extreme_comparisons)]
5192 #[allow(unused_comparisons)]
5193 if __tmp.remaining() < Self::ENCODED_LEN {
5194 panic!(
5195 "buffer is too small (need {} bytes, but got {})",
5196 Self::ENCODED_LEN,
5197 __tmp.remaining(),
5198 )
5199 }
5200 __tmp.put_u8(self.target_system);
5201 __tmp.put_u8(self.target_component);
5202 for val in &self.id_or_mac {
5203 __tmp.put_u8(*val);
5204 }
5205 __tmp.put_u8(self.single_message_size);
5206 __tmp.put_u8(self.msg_pack_size);
5207 for val in &self.messages {
5208 __tmp.put_u8(*val);
5209 }
5210 if matches!(version, MavlinkVersion::V2) {
5211 let len = __tmp.len();
5212 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5213 } else {
5214 __tmp.len()
5215 }
5216 }
5217}
5218#[doc = "id: 61"]
5219#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
5220#[derive(Debug, Clone, PartialEq)]
5221#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5222#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5223pub struct ATTITUDE_QUATERNION_COV_DATA {
5224 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5225 pub time_usec: u64,
5226 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
5227 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5228 pub q: [f32; 4],
5229 #[doc = "Roll angular speed"]
5230 pub rollspeed: f32,
5231 #[doc = "Pitch angular speed"]
5232 pub pitchspeed: f32,
5233 #[doc = "Yaw angular speed"]
5234 pub yawspeed: f32,
5235 #[doc = "Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
5236 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5237 pub covariance: [f32; 9],
5238}
5239impl ATTITUDE_QUATERNION_COV_DATA {
5240 pub const ENCODED_LEN: usize = 72usize;
5241 pub const DEFAULT: Self = Self {
5242 time_usec: 0_u64,
5243 q: [0.0_f32; 4usize],
5244 rollspeed: 0.0_f32,
5245 pitchspeed: 0.0_f32,
5246 yawspeed: 0.0_f32,
5247 covariance: [0.0_f32; 9usize],
5248 };
5249 #[cfg(feature = "arbitrary")]
5250 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5251 use arbitrary::{Arbitrary, Unstructured};
5252 let mut buf = [0u8; 1024];
5253 rng.fill_bytes(&mut buf);
5254 let mut unstructured = Unstructured::new(&buf);
5255 Self::arbitrary(&mut unstructured).unwrap_or_default()
5256 }
5257}
5258impl Default for ATTITUDE_QUATERNION_COV_DATA {
5259 fn default() -> Self {
5260 Self::DEFAULT.clone()
5261 }
5262}
5263impl MessageData for ATTITUDE_QUATERNION_COV_DATA {
5264 type Message = MavMessage;
5265 const ID: u32 = 61u32;
5266 const NAME: &'static str = "ATTITUDE_QUATERNION_COV";
5267 const EXTRA_CRC: u8 = 167u8;
5268 const ENCODED_LEN: usize = 72usize;
5269 fn deser(
5270 _version: MavlinkVersion,
5271 __input: &[u8],
5272 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5273 let avail_len = __input.len();
5274 let mut payload_buf = [0; Self::ENCODED_LEN];
5275 let mut buf = if avail_len < Self::ENCODED_LEN {
5276 payload_buf[0..avail_len].copy_from_slice(__input);
5277 Bytes::new(&payload_buf)
5278 } else {
5279 Bytes::new(__input)
5280 };
5281 let mut __struct = Self::default();
5282 __struct.time_usec = buf.get_u64_le();
5283 for v in &mut __struct.q {
5284 let val = buf.get_f32_le();
5285 *v = val;
5286 }
5287 __struct.rollspeed = buf.get_f32_le();
5288 __struct.pitchspeed = buf.get_f32_le();
5289 __struct.yawspeed = buf.get_f32_le();
5290 for v in &mut __struct.covariance {
5291 let val = buf.get_f32_le();
5292 *v = val;
5293 }
5294 Ok(__struct)
5295 }
5296 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5297 let mut __tmp = BytesMut::new(bytes);
5298 #[allow(clippy::absurd_extreme_comparisons)]
5299 #[allow(unused_comparisons)]
5300 if __tmp.remaining() < Self::ENCODED_LEN {
5301 panic!(
5302 "buffer is too small (need {} bytes, but got {})",
5303 Self::ENCODED_LEN,
5304 __tmp.remaining(),
5305 )
5306 }
5307 __tmp.put_u64_le(self.time_usec);
5308 for val in &self.q {
5309 __tmp.put_f32_le(*val);
5310 }
5311 __tmp.put_f32_le(self.rollspeed);
5312 __tmp.put_f32_le(self.pitchspeed);
5313 __tmp.put_f32_le(self.yawspeed);
5314 for val in &self.covariance {
5315 __tmp.put_f32_le(*val);
5316 }
5317 if matches!(version, MavlinkVersion::V2) {
5318 let len = __tmp.len();
5319 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5320 } else {
5321 __tmp.len()
5322 }
5323 }
5324}
5325#[doc = "id: 373"]
5326#[doc = "Telemetry of power generation system. Alternator or mechanical generator."]
5327#[derive(Debug, Clone, PartialEq)]
5328#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5329#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5330pub struct GENERATOR_STATUS_DATA {
5331 #[doc = "Status flags."]
5332 pub status: MavGeneratorStatusFlag,
5333 #[doc = "Current into/out of battery. Positive for out. Negative for in. NaN: field not provided."]
5334 pub battery_current: f32,
5335 #[doc = "Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided"]
5336 pub load_current: f32,
5337 #[doc = "The power being generated. NaN: field not provided"]
5338 pub power_generated: f32,
5339 #[doc = "Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus."]
5340 pub bus_voltage: f32,
5341 #[doc = "The target battery current. Positive for out. Negative for in. NaN: field not provided"]
5342 pub bat_current_setpoint: f32,
5343 #[doc = "Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided."]
5344 pub runtime: u32,
5345 #[doc = "Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided."]
5346 pub time_until_maintenance: i32,
5347 #[doc = "Speed of electrical generator or alternator. UINT16_MAX: field not provided."]
5348 pub generator_speed: u16,
5349 #[doc = "The temperature of the rectifier or power converter. INT16_MAX: field not provided."]
5350 pub rectifier_temperature: i16,
5351 #[doc = "The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided."]
5352 pub generator_temperature: i16,
5353}
5354impl GENERATOR_STATUS_DATA {
5355 pub const ENCODED_LEN: usize = 42usize;
5356 pub const DEFAULT: Self = Self {
5357 status: MavGeneratorStatusFlag::DEFAULT,
5358 battery_current: 0.0_f32,
5359 load_current: 0.0_f32,
5360 power_generated: 0.0_f32,
5361 bus_voltage: 0.0_f32,
5362 bat_current_setpoint: 0.0_f32,
5363 runtime: 0_u32,
5364 time_until_maintenance: 0_i32,
5365 generator_speed: 0_u16,
5366 rectifier_temperature: 0_i16,
5367 generator_temperature: 0_i16,
5368 };
5369 #[cfg(feature = "arbitrary")]
5370 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5371 use arbitrary::{Arbitrary, Unstructured};
5372 let mut buf = [0u8; 1024];
5373 rng.fill_bytes(&mut buf);
5374 let mut unstructured = Unstructured::new(&buf);
5375 Self::arbitrary(&mut unstructured).unwrap_or_default()
5376 }
5377}
5378impl Default for GENERATOR_STATUS_DATA {
5379 fn default() -> Self {
5380 Self::DEFAULT.clone()
5381 }
5382}
5383impl MessageData for GENERATOR_STATUS_DATA {
5384 type Message = MavMessage;
5385 const ID: u32 = 373u32;
5386 const NAME: &'static str = "GENERATOR_STATUS";
5387 const EXTRA_CRC: u8 = 117u8;
5388 const ENCODED_LEN: usize = 42usize;
5389 fn deser(
5390 _version: MavlinkVersion,
5391 __input: &[u8],
5392 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5393 let avail_len = __input.len();
5394 let mut payload_buf = [0; Self::ENCODED_LEN];
5395 let mut buf = if avail_len < Self::ENCODED_LEN {
5396 payload_buf[0..avail_len].copy_from_slice(__input);
5397 Bytes::new(&payload_buf)
5398 } else {
5399 Bytes::new(__input)
5400 };
5401 let mut __struct = Self::default();
5402 let tmp = buf.get_u64_le();
5403 __struct.status = MavGeneratorStatusFlag::from_bits(
5404 tmp & MavGeneratorStatusFlag::all().bits(),
5405 )
5406 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5407 flag_type: "MavGeneratorStatusFlag",
5408 value: tmp as u32,
5409 })?;
5410 __struct.battery_current = buf.get_f32_le();
5411 __struct.load_current = buf.get_f32_le();
5412 __struct.power_generated = buf.get_f32_le();
5413 __struct.bus_voltage = buf.get_f32_le();
5414 __struct.bat_current_setpoint = buf.get_f32_le();
5415 __struct.runtime = buf.get_u32_le();
5416 __struct.time_until_maintenance = buf.get_i32_le();
5417 __struct.generator_speed = buf.get_u16_le();
5418 __struct.rectifier_temperature = buf.get_i16_le();
5419 __struct.generator_temperature = buf.get_i16_le();
5420 Ok(__struct)
5421 }
5422 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5423 let mut __tmp = BytesMut::new(bytes);
5424 #[allow(clippy::absurd_extreme_comparisons)]
5425 #[allow(unused_comparisons)]
5426 if __tmp.remaining() < Self::ENCODED_LEN {
5427 panic!(
5428 "buffer is too small (need {} bytes, but got {})",
5429 Self::ENCODED_LEN,
5430 __tmp.remaining(),
5431 )
5432 }
5433 __tmp.put_u64_le(self.status.bits());
5434 __tmp.put_f32_le(self.battery_current);
5435 __tmp.put_f32_le(self.load_current);
5436 __tmp.put_f32_le(self.power_generated);
5437 __tmp.put_f32_le(self.bus_voltage);
5438 __tmp.put_f32_le(self.bat_current_setpoint);
5439 __tmp.put_u32_le(self.runtime);
5440 __tmp.put_i32_le(self.time_until_maintenance);
5441 __tmp.put_u16_le(self.generator_speed);
5442 __tmp.put_i16_le(self.rectifier_temperature);
5443 __tmp.put_i16_le(self.generator_temperature);
5444 if matches!(version, MavlinkVersion::V2) {
5445 let len = __tmp.len();
5446 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5447 } else {
5448 __tmp.len()
5449 }
5450 }
5451}
5452#[doc = "id: 110"]
5453#[doc = "File transfer protocol message: <https://mavlink.io/en/services/ftp.html>."]
5454#[derive(Debug, Clone, PartialEq)]
5455#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5456#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5457pub struct FILE_TRANSFER_PROTOCOL_DATA {
5458 #[doc = "Network ID (0 for broadcast)"]
5459 pub target_network: u8,
5460 #[doc = "System ID (0 for broadcast)"]
5461 pub target_system: u8,
5462 #[doc = "Component ID (0 for broadcast)"]
5463 pub target_component: u8,
5464 #[doc = "Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in <https://mavlink.io/en/services/ftp.html>."]
5465 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5466 pub payload: [u8; 251],
5467}
5468impl FILE_TRANSFER_PROTOCOL_DATA {
5469 pub const ENCODED_LEN: usize = 254usize;
5470 pub const DEFAULT: Self = Self {
5471 target_network: 0_u8,
5472 target_system: 0_u8,
5473 target_component: 0_u8,
5474 payload: [0_u8; 251usize],
5475 };
5476 #[cfg(feature = "arbitrary")]
5477 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5478 use arbitrary::{Arbitrary, Unstructured};
5479 let mut buf = [0u8; 1024];
5480 rng.fill_bytes(&mut buf);
5481 let mut unstructured = Unstructured::new(&buf);
5482 Self::arbitrary(&mut unstructured).unwrap_or_default()
5483 }
5484}
5485impl Default for FILE_TRANSFER_PROTOCOL_DATA {
5486 fn default() -> Self {
5487 Self::DEFAULT.clone()
5488 }
5489}
5490impl MessageData for FILE_TRANSFER_PROTOCOL_DATA {
5491 type Message = MavMessage;
5492 const ID: u32 = 110u32;
5493 const NAME: &'static str = "FILE_TRANSFER_PROTOCOL";
5494 const EXTRA_CRC: u8 = 84u8;
5495 const ENCODED_LEN: usize = 254usize;
5496 fn deser(
5497 _version: MavlinkVersion,
5498 __input: &[u8],
5499 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5500 let avail_len = __input.len();
5501 let mut payload_buf = [0; Self::ENCODED_LEN];
5502 let mut buf = if avail_len < Self::ENCODED_LEN {
5503 payload_buf[0..avail_len].copy_from_slice(__input);
5504 Bytes::new(&payload_buf)
5505 } else {
5506 Bytes::new(__input)
5507 };
5508 let mut __struct = Self::default();
5509 __struct.target_network = buf.get_u8();
5510 __struct.target_system = buf.get_u8();
5511 __struct.target_component = buf.get_u8();
5512 for v in &mut __struct.payload {
5513 let val = buf.get_u8();
5514 *v = val;
5515 }
5516 Ok(__struct)
5517 }
5518 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5519 let mut __tmp = BytesMut::new(bytes);
5520 #[allow(clippy::absurd_extreme_comparisons)]
5521 #[allow(unused_comparisons)]
5522 if __tmp.remaining() < Self::ENCODED_LEN {
5523 panic!(
5524 "buffer is too small (need {} bytes, but got {})",
5525 Self::ENCODED_LEN,
5526 __tmp.remaining(),
5527 )
5528 }
5529 __tmp.put_u8(self.target_network);
5530 __tmp.put_u8(self.target_system);
5531 __tmp.put_u8(self.target_component);
5532 for val in &self.payload {
5533 __tmp.put_u8(*val);
5534 }
5535 if matches!(version, MavlinkVersion::V2) {
5536 let len = __tmp.len();
5537 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5538 } else {
5539 __tmp.len()
5540 }
5541 }
5542}
5543#[doc = "id: 375"]
5544#[doc = "The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW."]
5545#[derive(Debug, Clone, PartialEq)]
5546#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5547#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5548pub struct ACTUATOR_OUTPUT_STATUS_DATA {
5549 #[doc = "Timestamp (since system boot)."]
5550 pub time_usec: u64,
5551 #[doc = "Active outputs"]
5552 pub active: u32,
5553 #[doc = "Servo / motor output array values. Zero values indicate unused channels."]
5554 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5555 pub actuator: [f32; 32],
5556}
5557impl ACTUATOR_OUTPUT_STATUS_DATA {
5558 pub const ENCODED_LEN: usize = 140usize;
5559 pub const DEFAULT: Self = Self {
5560 time_usec: 0_u64,
5561 active: 0_u32,
5562 actuator: [0.0_f32; 32usize],
5563 };
5564 #[cfg(feature = "arbitrary")]
5565 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5566 use arbitrary::{Arbitrary, Unstructured};
5567 let mut buf = [0u8; 1024];
5568 rng.fill_bytes(&mut buf);
5569 let mut unstructured = Unstructured::new(&buf);
5570 Self::arbitrary(&mut unstructured).unwrap_or_default()
5571 }
5572}
5573impl Default for ACTUATOR_OUTPUT_STATUS_DATA {
5574 fn default() -> Self {
5575 Self::DEFAULT.clone()
5576 }
5577}
5578impl MessageData for ACTUATOR_OUTPUT_STATUS_DATA {
5579 type Message = MavMessage;
5580 const ID: u32 = 375u32;
5581 const NAME: &'static str = "ACTUATOR_OUTPUT_STATUS";
5582 const EXTRA_CRC: u8 = 251u8;
5583 const ENCODED_LEN: usize = 140usize;
5584 fn deser(
5585 _version: MavlinkVersion,
5586 __input: &[u8],
5587 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5588 let avail_len = __input.len();
5589 let mut payload_buf = [0; Self::ENCODED_LEN];
5590 let mut buf = if avail_len < Self::ENCODED_LEN {
5591 payload_buf[0..avail_len].copy_from_slice(__input);
5592 Bytes::new(&payload_buf)
5593 } else {
5594 Bytes::new(__input)
5595 };
5596 let mut __struct = Self::default();
5597 __struct.time_usec = buf.get_u64_le();
5598 __struct.active = buf.get_u32_le();
5599 for v in &mut __struct.actuator {
5600 let val = buf.get_f32_le();
5601 *v = val;
5602 }
5603 Ok(__struct)
5604 }
5605 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5606 let mut __tmp = BytesMut::new(bytes);
5607 #[allow(clippy::absurd_extreme_comparisons)]
5608 #[allow(unused_comparisons)]
5609 if __tmp.remaining() < Self::ENCODED_LEN {
5610 panic!(
5611 "buffer is too small (need {} bytes, but got {})",
5612 Self::ENCODED_LEN,
5613 __tmp.remaining(),
5614 )
5615 }
5616 __tmp.put_u64_le(self.time_usec);
5617 __tmp.put_u32_le(self.active);
5618 for val in &self.actuator {
5619 __tmp.put_f32_le(*val);
5620 }
5621 if matches!(version, MavlinkVersion::V2) {
5622 let len = __tmp.len();
5623 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5624 } else {
5625 __tmp.len()
5626 }
5627 }
5628}
5629#[doc = "id: 396"]
5630#[doc = "Basic component information data. Should be requested using MAV_CMD_REQUEST_MESSAGE on startup, or when required."]
5631#[derive(Debug, Clone, PartialEq)]
5632#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5633#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5634pub struct COMPONENT_INFORMATION_BASIC_DATA {
5635 #[doc = "Component capability flags"]
5636 pub capabilities: MavProtocolCapability,
5637 #[doc = "Timestamp (time since system boot)."]
5638 pub time_boot_ms: u32,
5639 #[doc = "Date of manufacture as a UNIX Epoch time (since 1.1.1970) in seconds."]
5640 pub time_manufacture_s: u32,
5641 #[doc = "Name of the component vendor. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
5642 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5643 pub vendor_name: [u8; 32],
5644 #[doc = "Name of the component model. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
5645 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5646 pub model_name: [u8; 32],
5647 #[doc = "Software version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
5648 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5649 pub software_version: [u8; 24],
5650 #[doc = "Hardware version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
5651 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5652 pub hardware_version: [u8; 24],
5653 #[doc = "Hardware serial number. The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
5654 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5655 pub serial_number: [u8; 32],
5656}
5657impl COMPONENT_INFORMATION_BASIC_DATA {
5658 pub const ENCODED_LEN: usize = 160usize;
5659 pub const DEFAULT: Self = Self {
5660 capabilities: MavProtocolCapability::DEFAULT,
5661 time_boot_ms: 0_u32,
5662 time_manufacture_s: 0_u32,
5663 vendor_name: [0_u8; 32usize],
5664 model_name: [0_u8; 32usize],
5665 software_version: [0_u8; 24usize],
5666 hardware_version: [0_u8; 24usize],
5667 serial_number: [0_u8; 32usize],
5668 };
5669 #[cfg(feature = "arbitrary")]
5670 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5671 use arbitrary::{Arbitrary, Unstructured};
5672 let mut buf = [0u8; 1024];
5673 rng.fill_bytes(&mut buf);
5674 let mut unstructured = Unstructured::new(&buf);
5675 Self::arbitrary(&mut unstructured).unwrap_or_default()
5676 }
5677}
5678impl Default for COMPONENT_INFORMATION_BASIC_DATA {
5679 fn default() -> Self {
5680 Self::DEFAULT.clone()
5681 }
5682}
5683impl MessageData for COMPONENT_INFORMATION_BASIC_DATA {
5684 type Message = MavMessage;
5685 const ID: u32 = 396u32;
5686 const NAME: &'static str = "COMPONENT_INFORMATION_BASIC";
5687 const EXTRA_CRC: u8 = 50u8;
5688 const ENCODED_LEN: usize = 160usize;
5689 fn deser(
5690 _version: MavlinkVersion,
5691 __input: &[u8],
5692 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5693 let avail_len = __input.len();
5694 let mut payload_buf = [0; Self::ENCODED_LEN];
5695 let mut buf = if avail_len < Self::ENCODED_LEN {
5696 payload_buf[0..avail_len].copy_from_slice(__input);
5697 Bytes::new(&payload_buf)
5698 } else {
5699 Bytes::new(__input)
5700 };
5701 let mut __struct = Self::default();
5702 let tmp = buf.get_u64_le();
5703 __struct.capabilities = MavProtocolCapability::from_bits(
5704 tmp & MavProtocolCapability::all().bits(),
5705 )
5706 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
5707 flag_type: "MavProtocolCapability",
5708 value: tmp as u32,
5709 })?;
5710 __struct.time_boot_ms = buf.get_u32_le();
5711 __struct.time_manufacture_s = buf.get_u32_le();
5712 for v in &mut __struct.vendor_name {
5713 let val = buf.get_u8();
5714 *v = val;
5715 }
5716 for v in &mut __struct.model_name {
5717 let val = buf.get_u8();
5718 *v = val;
5719 }
5720 for v in &mut __struct.software_version {
5721 let val = buf.get_u8();
5722 *v = val;
5723 }
5724 for v in &mut __struct.hardware_version {
5725 let val = buf.get_u8();
5726 *v = val;
5727 }
5728 for v in &mut __struct.serial_number {
5729 let val = buf.get_u8();
5730 *v = val;
5731 }
5732 Ok(__struct)
5733 }
5734 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5735 let mut __tmp = BytesMut::new(bytes);
5736 #[allow(clippy::absurd_extreme_comparisons)]
5737 #[allow(unused_comparisons)]
5738 if __tmp.remaining() < Self::ENCODED_LEN {
5739 panic!(
5740 "buffer is too small (need {} bytes, but got {})",
5741 Self::ENCODED_LEN,
5742 __tmp.remaining(),
5743 )
5744 }
5745 __tmp.put_u64_le(self.capabilities.bits());
5746 __tmp.put_u32_le(self.time_boot_ms);
5747 __tmp.put_u32_le(self.time_manufacture_s);
5748 for val in &self.vendor_name {
5749 __tmp.put_u8(*val);
5750 }
5751 for val in &self.model_name {
5752 __tmp.put_u8(*val);
5753 }
5754 for val in &self.software_version {
5755 __tmp.put_u8(*val);
5756 }
5757 for val in &self.hardware_version {
5758 __tmp.put_u8(*val);
5759 }
5760 for val in &self.serial_number {
5761 __tmp.put_u8(*val);
5762 }
5763 if matches!(version, MavlinkVersion::V2) {
5764 let len = __tmp.len();
5765 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5766 } else {
5767 __tmp.len()
5768 }
5769 }
5770}
5771#[doc = "id: 371"]
5772#[doc = "Fuel status. This message provides \"generic\" fuel level information for in a GCS and for triggering failsafes in an autopilot. The fuel type and associated units for fields in this message are defined in the enum MAV_FUEL_TYPE. The reported `consumed_fuel` and `remaining_fuel` must only be supplied if measured: they must not be inferred from the `maximum_fuel` and the other value. A recipient can assume that if these fields are supplied they are accurate. If not provided, the recipient can infer `remaining_fuel` from `maximum_fuel` and `consumed_fuel` on the assumption that the fuel was initially at its maximum (this is what battery monitors assume). Note however that this is an assumption, and the UI should prompt the user appropriately (i.e. notify user that they should fill the tank before boot). This kind of information may also be sent in fuel-specific messages such as BATTERY_STATUS_V2. If both messages are sent for the same fuel system, the ids and corresponding information must match. This should be streamed (nominally at 0.1 Hz)."]
5773#[derive(Debug, Clone, PartialEq)]
5774#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5775#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5776pub struct FUEL_STATUS_DATA {
5777 #[doc = "Capacity when full. Must be provided."]
5778 pub maximum_fuel: f32,
5779 #[doc = "Consumed fuel (measured). This value should not be inferred: if not measured set to NaN. NaN: field not provided."]
5780 pub consumed_fuel: f32,
5781 #[doc = "Remaining fuel until empty (measured). The value should not be inferred: if not measured set to NaN. NaN: field not provided."]
5782 pub remaining_fuel: f32,
5783 #[doc = "Positive value when emptying/using, and negative if filling/replacing. NaN: field not provided."]
5784 pub flow_rate: f32,
5785 #[doc = "Fuel temperature. NaN: field not provided."]
5786 pub temperature: f32,
5787 #[doc = "Fuel type. Defines units for fuel capacity and consumption fields above."]
5788 pub fuel_type: MavFuelType,
5789 #[doc = "Fuel ID. Must match ID of other messages for same fuel system, such as BATTERY_STATUS_V2."]
5790 pub id: u8,
5791 #[doc = "Percentage of remaining fuel, relative to full. Values: [0-100], UINT8_MAX: field not provided."]
5792 pub percent_remaining: u8,
5793}
5794impl FUEL_STATUS_DATA {
5795 pub const ENCODED_LEN: usize = 26usize;
5796 pub const DEFAULT: Self = Self {
5797 maximum_fuel: 0.0_f32,
5798 consumed_fuel: 0.0_f32,
5799 remaining_fuel: 0.0_f32,
5800 flow_rate: 0.0_f32,
5801 temperature: 0.0_f32,
5802 fuel_type: MavFuelType::DEFAULT,
5803 id: 0_u8,
5804 percent_remaining: 0_u8,
5805 };
5806 #[cfg(feature = "arbitrary")]
5807 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5808 use arbitrary::{Arbitrary, Unstructured};
5809 let mut buf = [0u8; 1024];
5810 rng.fill_bytes(&mut buf);
5811 let mut unstructured = Unstructured::new(&buf);
5812 Self::arbitrary(&mut unstructured).unwrap_or_default()
5813 }
5814}
5815impl Default for FUEL_STATUS_DATA {
5816 fn default() -> Self {
5817 Self::DEFAULT.clone()
5818 }
5819}
5820impl MessageData for FUEL_STATUS_DATA {
5821 type Message = MavMessage;
5822 const ID: u32 = 371u32;
5823 const NAME: &'static str = "FUEL_STATUS";
5824 const EXTRA_CRC: u8 = 10u8;
5825 const ENCODED_LEN: usize = 26usize;
5826 fn deser(
5827 _version: MavlinkVersion,
5828 __input: &[u8],
5829 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5830 let avail_len = __input.len();
5831 let mut payload_buf = [0; Self::ENCODED_LEN];
5832 let mut buf = if avail_len < Self::ENCODED_LEN {
5833 payload_buf[0..avail_len].copy_from_slice(__input);
5834 Bytes::new(&payload_buf)
5835 } else {
5836 Bytes::new(__input)
5837 };
5838 let mut __struct = Self::default();
5839 __struct.maximum_fuel = buf.get_f32_le();
5840 __struct.consumed_fuel = buf.get_f32_le();
5841 __struct.remaining_fuel = buf.get_f32_le();
5842 __struct.flow_rate = buf.get_f32_le();
5843 __struct.temperature = buf.get_f32_le();
5844 let tmp = buf.get_u32_le();
5845 __struct.fuel_type = FromPrimitive::from_u32(tmp).ok_or(
5846 ::mavlink_core::error::ParserError::InvalidEnum {
5847 enum_type: "MavFuelType",
5848 value: tmp as u32,
5849 },
5850 )?;
5851 __struct.id = buf.get_u8();
5852 __struct.percent_remaining = buf.get_u8();
5853 Ok(__struct)
5854 }
5855 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5856 let mut __tmp = BytesMut::new(bytes);
5857 #[allow(clippy::absurd_extreme_comparisons)]
5858 #[allow(unused_comparisons)]
5859 if __tmp.remaining() < Self::ENCODED_LEN {
5860 panic!(
5861 "buffer is too small (need {} bytes, but got {})",
5862 Self::ENCODED_LEN,
5863 __tmp.remaining(),
5864 )
5865 }
5866 __tmp.put_f32_le(self.maximum_fuel);
5867 __tmp.put_f32_le(self.consumed_fuel);
5868 __tmp.put_f32_le(self.remaining_fuel);
5869 __tmp.put_f32_le(self.flow_rate);
5870 __tmp.put_f32_le(self.temperature);
5871 __tmp.put_u32_le(self.fuel_type as u32);
5872 __tmp.put_u8(self.id);
5873 __tmp.put_u8(self.percent_remaining);
5874 if matches!(version, MavlinkVersion::V2) {
5875 let len = __tmp.len();
5876 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5877 } else {
5878 __tmp.len()
5879 }
5880 }
5881}
5882#[doc = "id: 12900"]
5883#[doc = "Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. <https://github.com/opendroneid/opendroneid-core-c>. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at <https://mavlink.io/en/services/opendroneid.html>."]
5884#[derive(Debug, Clone, PartialEq)]
5885#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5886#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5887pub struct OPEN_DRONE_ID_BASIC_ID_DATA {
5888 #[doc = "System ID (0 for broadcast)."]
5889 pub target_system: u8,
5890 #[doc = "Component ID (0 for broadcast)."]
5891 pub target_component: u8,
5892 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
5893 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5894 pub id_or_mac: [u8; 20],
5895 #[doc = "Indicates the format for the uas_id field of this message."]
5896 pub id_type: MavOdidIdType,
5897 #[doc = "Indicates the type of UA (Unmanned Aircraft)."]
5898 pub ua_type: MavOdidUaType,
5899 #[doc = "UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field."]
5900 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5901 pub uas_id: [u8; 20],
5902}
5903impl OPEN_DRONE_ID_BASIC_ID_DATA {
5904 pub const ENCODED_LEN: usize = 44usize;
5905 pub const DEFAULT: Self = Self {
5906 target_system: 0_u8,
5907 target_component: 0_u8,
5908 id_or_mac: [0_u8; 20usize],
5909 id_type: MavOdidIdType::DEFAULT,
5910 ua_type: MavOdidUaType::DEFAULT,
5911 uas_id: [0_u8; 20usize],
5912 };
5913 #[cfg(feature = "arbitrary")]
5914 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5915 use arbitrary::{Arbitrary, Unstructured};
5916 let mut buf = [0u8; 1024];
5917 rng.fill_bytes(&mut buf);
5918 let mut unstructured = Unstructured::new(&buf);
5919 Self::arbitrary(&mut unstructured).unwrap_or_default()
5920 }
5921}
5922impl Default for OPEN_DRONE_ID_BASIC_ID_DATA {
5923 fn default() -> Self {
5924 Self::DEFAULT.clone()
5925 }
5926}
5927impl MessageData for OPEN_DRONE_ID_BASIC_ID_DATA {
5928 type Message = MavMessage;
5929 const ID: u32 = 12900u32;
5930 const NAME: &'static str = "OPEN_DRONE_ID_BASIC_ID";
5931 const EXTRA_CRC: u8 = 114u8;
5932 const ENCODED_LEN: usize = 44usize;
5933 fn deser(
5934 _version: MavlinkVersion,
5935 __input: &[u8],
5936 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5937 let avail_len = __input.len();
5938 let mut payload_buf = [0; Self::ENCODED_LEN];
5939 let mut buf = if avail_len < Self::ENCODED_LEN {
5940 payload_buf[0..avail_len].copy_from_slice(__input);
5941 Bytes::new(&payload_buf)
5942 } else {
5943 Bytes::new(__input)
5944 };
5945 let mut __struct = Self::default();
5946 __struct.target_system = buf.get_u8();
5947 __struct.target_component = buf.get_u8();
5948 for v in &mut __struct.id_or_mac {
5949 let val = buf.get_u8();
5950 *v = val;
5951 }
5952 let tmp = buf.get_u8();
5953 __struct.id_type =
5954 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5955 enum_type: "MavOdidIdType",
5956 value: tmp as u32,
5957 })?;
5958 let tmp = buf.get_u8();
5959 __struct.ua_type =
5960 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5961 enum_type: "MavOdidUaType",
5962 value: tmp as u32,
5963 })?;
5964 for v in &mut __struct.uas_id {
5965 let val = buf.get_u8();
5966 *v = val;
5967 }
5968 Ok(__struct)
5969 }
5970 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5971 let mut __tmp = BytesMut::new(bytes);
5972 #[allow(clippy::absurd_extreme_comparisons)]
5973 #[allow(unused_comparisons)]
5974 if __tmp.remaining() < Self::ENCODED_LEN {
5975 panic!(
5976 "buffer is too small (need {} bytes, but got {})",
5977 Self::ENCODED_LEN,
5978 __tmp.remaining(),
5979 )
5980 }
5981 __tmp.put_u8(self.target_system);
5982 __tmp.put_u8(self.target_component);
5983 for val in &self.id_or_mac {
5984 __tmp.put_u8(*val);
5985 }
5986 __tmp.put_u8(self.id_type as u8);
5987 __tmp.put_u8(self.ua_type as u8);
5988 for val in &self.uas_id {
5989 __tmp.put_u8(*val);
5990 }
5991 if matches!(version, MavlinkVersion::V2) {
5992 let len = __tmp.len();
5993 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5994 } else {
5995 __tmp.len()
5996 }
5997 }
5998}
5999#[doc = "id: 230"]
6000#[doc = "Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user."]
6001#[derive(Debug, Clone, PartialEq)]
6002#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6003#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6004pub struct ESTIMATOR_STATUS_DATA {
6005 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
6006 pub time_usec: u64,
6007 #[doc = "Velocity innovation test ratio"]
6008 pub vel_ratio: f32,
6009 #[doc = "Horizontal position innovation test ratio"]
6010 pub pos_horiz_ratio: f32,
6011 #[doc = "Vertical position innovation test ratio"]
6012 pub pos_vert_ratio: f32,
6013 #[doc = "Magnetometer innovation test ratio"]
6014 pub mag_ratio: f32,
6015 #[doc = "Height above terrain innovation test ratio"]
6016 pub hagl_ratio: f32,
6017 #[doc = "True airspeed innovation test ratio"]
6018 pub tas_ratio: f32,
6019 #[doc = "Horizontal position 1-STD accuracy relative to the EKF local origin"]
6020 pub pos_horiz_accuracy: f32,
6021 #[doc = "Vertical position 1-STD accuracy relative to the EKF local origin"]
6022 pub pos_vert_accuracy: f32,
6023 #[doc = "Bitmap indicating which EKF outputs are valid."]
6024 pub flags: EstimatorStatusFlags,
6025}
6026impl ESTIMATOR_STATUS_DATA {
6027 pub const ENCODED_LEN: usize = 42usize;
6028 pub const DEFAULT: Self = Self {
6029 time_usec: 0_u64,
6030 vel_ratio: 0.0_f32,
6031 pos_horiz_ratio: 0.0_f32,
6032 pos_vert_ratio: 0.0_f32,
6033 mag_ratio: 0.0_f32,
6034 hagl_ratio: 0.0_f32,
6035 tas_ratio: 0.0_f32,
6036 pos_horiz_accuracy: 0.0_f32,
6037 pos_vert_accuracy: 0.0_f32,
6038 flags: EstimatorStatusFlags::DEFAULT,
6039 };
6040 #[cfg(feature = "arbitrary")]
6041 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6042 use arbitrary::{Arbitrary, Unstructured};
6043 let mut buf = [0u8; 1024];
6044 rng.fill_bytes(&mut buf);
6045 let mut unstructured = Unstructured::new(&buf);
6046 Self::arbitrary(&mut unstructured).unwrap_or_default()
6047 }
6048}
6049impl Default for ESTIMATOR_STATUS_DATA {
6050 fn default() -> Self {
6051 Self::DEFAULT.clone()
6052 }
6053}
6054impl MessageData for ESTIMATOR_STATUS_DATA {
6055 type Message = MavMessage;
6056 const ID: u32 = 230u32;
6057 const NAME: &'static str = "ESTIMATOR_STATUS";
6058 const EXTRA_CRC: u8 = 163u8;
6059 const ENCODED_LEN: usize = 42usize;
6060 fn deser(
6061 _version: MavlinkVersion,
6062 __input: &[u8],
6063 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6064 let avail_len = __input.len();
6065 let mut payload_buf = [0; Self::ENCODED_LEN];
6066 let mut buf = if avail_len < Self::ENCODED_LEN {
6067 payload_buf[0..avail_len].copy_from_slice(__input);
6068 Bytes::new(&payload_buf)
6069 } else {
6070 Bytes::new(__input)
6071 };
6072 let mut __struct = Self::default();
6073 __struct.time_usec = buf.get_u64_le();
6074 __struct.vel_ratio = buf.get_f32_le();
6075 __struct.pos_horiz_ratio = buf.get_f32_le();
6076 __struct.pos_vert_ratio = buf.get_f32_le();
6077 __struct.mag_ratio = buf.get_f32_le();
6078 __struct.hagl_ratio = buf.get_f32_le();
6079 __struct.tas_ratio = buf.get_f32_le();
6080 __struct.pos_horiz_accuracy = buf.get_f32_le();
6081 __struct.pos_vert_accuracy = buf.get_f32_le();
6082 let tmp = buf.get_u16_le();
6083 __struct.flags = EstimatorStatusFlags::from_bits(tmp & EstimatorStatusFlags::all().bits())
6084 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
6085 flag_type: "EstimatorStatusFlags",
6086 value: tmp as u32,
6087 })?;
6088 Ok(__struct)
6089 }
6090 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6091 let mut __tmp = BytesMut::new(bytes);
6092 #[allow(clippy::absurd_extreme_comparisons)]
6093 #[allow(unused_comparisons)]
6094 if __tmp.remaining() < Self::ENCODED_LEN {
6095 panic!(
6096 "buffer is too small (need {} bytes, but got {})",
6097 Self::ENCODED_LEN,
6098 __tmp.remaining(),
6099 )
6100 }
6101 __tmp.put_u64_le(self.time_usec);
6102 __tmp.put_f32_le(self.vel_ratio);
6103 __tmp.put_f32_le(self.pos_horiz_ratio);
6104 __tmp.put_f32_le(self.pos_vert_ratio);
6105 __tmp.put_f32_le(self.mag_ratio);
6106 __tmp.put_f32_le(self.hagl_ratio);
6107 __tmp.put_f32_le(self.tas_ratio);
6108 __tmp.put_f32_le(self.pos_horiz_accuracy);
6109 __tmp.put_f32_le(self.pos_vert_accuracy);
6110 __tmp.put_u16_le(self.flags.bits());
6111 if matches!(version, MavlinkVersion::V2) {
6112 let len = __tmp.len();
6113 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6114 } else {
6115 __tmp.len()
6116 }
6117 }
6118}
6119#[doc = "id: 42"]
6120#[doc = "Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). This message should be streamed all the time (nominally at 1Hz). This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or MISSION_SET_CURRENT."]
6121#[derive(Debug, Clone, PartialEq)]
6122#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6123#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6124pub struct MISSION_CURRENT_DATA {
6125 #[doc = "Sequence"]
6126 pub seq: u16,
6127 #[doc = "Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle."]
6128 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6129 pub total: u16,
6130 #[doc = "Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported."]
6131 #[cfg_attr(feature = "serde", serde(default))]
6132 pub mission_state: MissionState,
6133 #[doc = "Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode)."]
6134 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6135 pub mission_mode: u8,
6136 #[doc = "Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK)."]
6137 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6138 pub mission_id: u32,
6139 #[doc = "Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK)."]
6140 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6141 pub fence_id: u32,
6142 #[doc = "Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK)."]
6143 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6144 pub rally_points_id: u32,
6145}
6146impl MISSION_CURRENT_DATA {
6147 pub const ENCODED_LEN: usize = 18usize;
6148 pub const DEFAULT: Self = Self {
6149 seq: 0_u16,
6150 total: 0_u16,
6151 mission_state: MissionState::DEFAULT,
6152 mission_mode: 0_u8,
6153 mission_id: 0_u32,
6154 fence_id: 0_u32,
6155 rally_points_id: 0_u32,
6156 };
6157 #[cfg(feature = "arbitrary")]
6158 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6159 use arbitrary::{Arbitrary, Unstructured};
6160 let mut buf = [0u8; 1024];
6161 rng.fill_bytes(&mut buf);
6162 let mut unstructured = Unstructured::new(&buf);
6163 Self::arbitrary(&mut unstructured).unwrap_or_default()
6164 }
6165}
6166impl Default for MISSION_CURRENT_DATA {
6167 fn default() -> Self {
6168 Self::DEFAULT.clone()
6169 }
6170}
6171impl MessageData for MISSION_CURRENT_DATA {
6172 type Message = MavMessage;
6173 const ID: u32 = 42u32;
6174 const NAME: &'static str = "MISSION_CURRENT";
6175 const EXTRA_CRC: u8 = 28u8;
6176 const ENCODED_LEN: usize = 18usize;
6177 fn deser(
6178 _version: MavlinkVersion,
6179 __input: &[u8],
6180 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6181 let avail_len = __input.len();
6182 let mut payload_buf = [0; Self::ENCODED_LEN];
6183 let mut buf = if avail_len < Self::ENCODED_LEN {
6184 payload_buf[0..avail_len].copy_from_slice(__input);
6185 Bytes::new(&payload_buf)
6186 } else {
6187 Bytes::new(__input)
6188 };
6189 let mut __struct = Self::default();
6190 __struct.seq = buf.get_u16_le();
6191 __struct.total = buf.get_u16_le();
6192 let tmp = buf.get_u8();
6193 __struct.mission_state =
6194 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6195 enum_type: "MissionState",
6196 value: tmp as u32,
6197 })?;
6198 __struct.mission_mode = buf.get_u8();
6199 __struct.mission_id = buf.get_u32_le();
6200 __struct.fence_id = buf.get_u32_le();
6201 __struct.rally_points_id = buf.get_u32_le();
6202 Ok(__struct)
6203 }
6204 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6205 let mut __tmp = BytesMut::new(bytes);
6206 #[allow(clippy::absurd_extreme_comparisons)]
6207 #[allow(unused_comparisons)]
6208 if __tmp.remaining() < Self::ENCODED_LEN {
6209 panic!(
6210 "buffer is too small (need {} bytes, but got {})",
6211 Self::ENCODED_LEN,
6212 __tmp.remaining(),
6213 )
6214 }
6215 __tmp.put_u16_le(self.seq);
6216 __tmp.put_u16_le(self.total);
6217 __tmp.put_u8(self.mission_state as u8);
6218 __tmp.put_u8(self.mission_mode);
6219 __tmp.put_u32_le(self.mission_id);
6220 __tmp.put_u32_le(self.fence_id);
6221 __tmp.put_u32_le(self.rally_points_id);
6222 if matches!(version, MavlinkVersion::V2) {
6223 let len = __tmp.len();
6224 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6225 } else {
6226 __tmp.len()
6227 }
6228 }
6229}
6230#[doc = "id: 285"]
6231#[doc = "Message reporting the status of a gimbal device. \t This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Other conditions of the flags are not allowed. \t The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as \t q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). \t If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, \t then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, \t and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN."]
6232#[derive(Debug, Clone, PartialEq)]
6233#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6234#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6235pub struct GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
6236 #[doc = "Timestamp (time since system boot)."]
6237 pub time_boot_ms: u32,
6238 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description."]
6239 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6240 pub q: [f32; 4],
6241 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown."]
6242 pub angular_velocity_x: f32,
6243 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown."]
6244 pub angular_velocity_y: f32,
6245 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown."]
6246 pub angular_velocity_z: f32,
6247 #[doc = "Failure flags (0 for no failure)"]
6248 pub failure_flags: GimbalDeviceErrorFlags,
6249 #[doc = "Current gimbal flags set."]
6250 pub flags: GimbalDeviceFlags,
6251 #[doc = "System ID"]
6252 pub target_system: u8,
6253 #[doc = "Component ID"]
6254 pub target_component: u8,
6255 #[doc = "Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown."]
6256 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6257 pub delta_yaw: f32,
6258 #[doc = "Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown."]
6259 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6260 pub delta_yaw_velocity: f32,
6261 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
6262 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6263 pub gimbal_device_id: u8,
6264}
6265impl GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
6266 pub const ENCODED_LEN: usize = 49usize;
6267 pub const DEFAULT: Self = Self {
6268 time_boot_ms: 0_u32,
6269 q: [0.0_f32; 4usize],
6270 angular_velocity_x: 0.0_f32,
6271 angular_velocity_y: 0.0_f32,
6272 angular_velocity_z: 0.0_f32,
6273 failure_flags: GimbalDeviceErrorFlags::DEFAULT,
6274 flags: GimbalDeviceFlags::DEFAULT,
6275 target_system: 0_u8,
6276 target_component: 0_u8,
6277 delta_yaw: 0.0_f32,
6278 delta_yaw_velocity: 0.0_f32,
6279 gimbal_device_id: 0_u8,
6280 };
6281 #[cfg(feature = "arbitrary")]
6282 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6283 use arbitrary::{Arbitrary, Unstructured};
6284 let mut buf = [0u8; 1024];
6285 rng.fill_bytes(&mut buf);
6286 let mut unstructured = Unstructured::new(&buf);
6287 Self::arbitrary(&mut unstructured).unwrap_or_default()
6288 }
6289}
6290impl Default for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
6291 fn default() -> Self {
6292 Self::DEFAULT.clone()
6293 }
6294}
6295impl MessageData for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
6296 type Message = MavMessage;
6297 const ID: u32 = 285u32;
6298 const NAME: &'static str = "GIMBAL_DEVICE_ATTITUDE_STATUS";
6299 const EXTRA_CRC: u8 = 137u8;
6300 const ENCODED_LEN: usize = 49usize;
6301 fn deser(
6302 _version: MavlinkVersion,
6303 __input: &[u8],
6304 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6305 let avail_len = __input.len();
6306 let mut payload_buf = [0; Self::ENCODED_LEN];
6307 let mut buf = if avail_len < Self::ENCODED_LEN {
6308 payload_buf[0..avail_len].copy_from_slice(__input);
6309 Bytes::new(&payload_buf)
6310 } else {
6311 Bytes::new(__input)
6312 };
6313 let mut __struct = Self::default();
6314 __struct.time_boot_ms = buf.get_u32_le();
6315 for v in &mut __struct.q {
6316 let val = buf.get_f32_le();
6317 *v = val;
6318 }
6319 __struct.angular_velocity_x = buf.get_f32_le();
6320 __struct.angular_velocity_y = buf.get_f32_le();
6321 __struct.angular_velocity_z = buf.get_f32_le();
6322 let tmp = buf.get_u32_le();
6323 __struct.failure_flags = GimbalDeviceErrorFlags::from_bits(
6324 tmp & GimbalDeviceErrorFlags::all().bits(),
6325 )
6326 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
6327 flag_type: "GimbalDeviceErrorFlags",
6328 value: tmp as u32,
6329 })?;
6330 let tmp = buf.get_u16_le();
6331 __struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits())
6332 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
6333 flag_type: "GimbalDeviceFlags",
6334 value: tmp as u32,
6335 })?;
6336 __struct.target_system = buf.get_u8();
6337 __struct.target_component = buf.get_u8();
6338 __struct.delta_yaw = buf.get_f32_le();
6339 __struct.delta_yaw_velocity = buf.get_f32_le();
6340 __struct.gimbal_device_id = buf.get_u8();
6341 Ok(__struct)
6342 }
6343 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6344 let mut __tmp = BytesMut::new(bytes);
6345 #[allow(clippy::absurd_extreme_comparisons)]
6346 #[allow(unused_comparisons)]
6347 if __tmp.remaining() < Self::ENCODED_LEN {
6348 panic!(
6349 "buffer is too small (need {} bytes, but got {})",
6350 Self::ENCODED_LEN,
6351 __tmp.remaining(),
6352 )
6353 }
6354 __tmp.put_u32_le(self.time_boot_ms);
6355 for val in &self.q {
6356 __tmp.put_f32_le(*val);
6357 }
6358 __tmp.put_f32_le(self.angular_velocity_x);
6359 __tmp.put_f32_le(self.angular_velocity_y);
6360 __tmp.put_f32_le(self.angular_velocity_z);
6361 __tmp.put_u32_le(self.failure_flags.bits());
6362 __tmp.put_u16_le(self.flags.bits());
6363 __tmp.put_u8(self.target_system);
6364 __tmp.put_u8(self.target_component);
6365 __tmp.put_f32_le(self.delta_yaw);
6366 __tmp.put_f32_le(self.delta_yaw_velocity);
6367 __tmp.put_u8(self.gimbal_device_id);
6368 if matches!(version, MavlinkVersion::V2) {
6369 let len = __tmp.len();
6370 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6371 } else {
6372 __tmp.len()
6373 }
6374 }
6375}
6376#[doc = "id: 33"]
6377#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient."]
6378#[derive(Debug, Clone, PartialEq)]
6379#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6380#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6381pub struct GLOBAL_POSITION_INT_DATA {
6382 #[doc = "Timestamp (time since system boot)."]
6383 pub time_boot_ms: u32,
6384 #[doc = "Latitude, expressed"]
6385 pub lat: i32,
6386 #[doc = "Longitude, expressed"]
6387 pub lon: i32,
6388 #[doc = "Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL."]
6389 pub alt: i32,
6390 #[doc = "Altitude above home"]
6391 pub relative_alt: i32,
6392 #[doc = "Ground X Speed (Latitude, positive north)"]
6393 pub vx: i16,
6394 #[doc = "Ground Y Speed (Longitude, positive east)"]
6395 pub vy: i16,
6396 #[doc = "Ground Z Speed (Altitude, positive down)"]
6397 pub vz: i16,
6398 #[doc = "Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
6399 pub hdg: u16,
6400}
6401impl GLOBAL_POSITION_INT_DATA {
6402 pub const ENCODED_LEN: usize = 28usize;
6403 pub const DEFAULT: Self = Self {
6404 time_boot_ms: 0_u32,
6405 lat: 0_i32,
6406 lon: 0_i32,
6407 alt: 0_i32,
6408 relative_alt: 0_i32,
6409 vx: 0_i16,
6410 vy: 0_i16,
6411 vz: 0_i16,
6412 hdg: 0_u16,
6413 };
6414 #[cfg(feature = "arbitrary")]
6415 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6416 use arbitrary::{Arbitrary, Unstructured};
6417 let mut buf = [0u8; 1024];
6418 rng.fill_bytes(&mut buf);
6419 let mut unstructured = Unstructured::new(&buf);
6420 Self::arbitrary(&mut unstructured).unwrap_or_default()
6421 }
6422}
6423impl Default for GLOBAL_POSITION_INT_DATA {
6424 fn default() -> Self {
6425 Self::DEFAULT.clone()
6426 }
6427}
6428impl MessageData for GLOBAL_POSITION_INT_DATA {
6429 type Message = MavMessage;
6430 const ID: u32 = 33u32;
6431 const NAME: &'static str = "GLOBAL_POSITION_INT";
6432 const EXTRA_CRC: u8 = 104u8;
6433 const ENCODED_LEN: usize = 28usize;
6434 fn deser(
6435 _version: MavlinkVersion,
6436 __input: &[u8],
6437 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6438 let avail_len = __input.len();
6439 let mut payload_buf = [0; Self::ENCODED_LEN];
6440 let mut buf = if avail_len < Self::ENCODED_LEN {
6441 payload_buf[0..avail_len].copy_from_slice(__input);
6442 Bytes::new(&payload_buf)
6443 } else {
6444 Bytes::new(__input)
6445 };
6446 let mut __struct = Self::default();
6447 __struct.time_boot_ms = buf.get_u32_le();
6448 __struct.lat = buf.get_i32_le();
6449 __struct.lon = buf.get_i32_le();
6450 __struct.alt = buf.get_i32_le();
6451 __struct.relative_alt = buf.get_i32_le();
6452 __struct.vx = buf.get_i16_le();
6453 __struct.vy = buf.get_i16_le();
6454 __struct.vz = buf.get_i16_le();
6455 __struct.hdg = buf.get_u16_le();
6456 Ok(__struct)
6457 }
6458 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6459 let mut __tmp = BytesMut::new(bytes);
6460 #[allow(clippy::absurd_extreme_comparisons)]
6461 #[allow(unused_comparisons)]
6462 if __tmp.remaining() < Self::ENCODED_LEN {
6463 panic!(
6464 "buffer is too small (need {} bytes, but got {})",
6465 Self::ENCODED_LEN,
6466 __tmp.remaining(),
6467 )
6468 }
6469 __tmp.put_u32_le(self.time_boot_ms);
6470 __tmp.put_i32_le(self.lat);
6471 __tmp.put_i32_le(self.lon);
6472 __tmp.put_i32_le(self.alt);
6473 __tmp.put_i32_le(self.relative_alt);
6474 __tmp.put_i16_le(self.vx);
6475 __tmp.put_i16_le(self.vy);
6476 __tmp.put_i16_le(self.vz);
6477 __tmp.put_u16_le(self.hdg);
6478 if matches!(version, MavlinkVersion::V2) {
6479 let len = __tmp.len();
6480 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6481 } else {
6482 __tmp.len()
6483 }
6484 }
6485}
6486#[doc = "id: 82"]
6487#[doc = "Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system)."]
6488#[derive(Debug, Clone, PartialEq)]
6489#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6490#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6491pub struct SET_ATTITUDE_TARGET_DATA {
6492 #[doc = "Timestamp (time since system boot)."]
6493 pub time_boot_ms: u32,
6494 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) from MAV_FRAME_LOCAL_NED to MAV_FRAME_BODY_FRD"]
6495 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6496 pub q: [f32; 4],
6497 #[doc = "Body roll rate"]
6498 pub body_roll_rate: f32,
6499 #[doc = "Body pitch rate"]
6500 pub body_pitch_rate: f32,
6501 #[doc = "Body yaw rate"]
6502 pub body_yaw_rate: f32,
6503 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
6504 pub thrust: f32,
6505 #[doc = "System ID"]
6506 pub target_system: u8,
6507 #[doc = "Component ID"]
6508 pub target_component: u8,
6509 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
6510 pub type_mask: AttitudeTargetTypemask,
6511 #[doc = "3D thrust setpoint in the body NED frame, normalized to -1 .. 1"]
6512 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6513 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6514 pub thrust_body: [f32; 3],
6515}
6516impl SET_ATTITUDE_TARGET_DATA {
6517 pub const ENCODED_LEN: usize = 51usize;
6518 pub const DEFAULT: Self = Self {
6519 time_boot_ms: 0_u32,
6520 q: [0.0_f32; 4usize],
6521 body_roll_rate: 0.0_f32,
6522 body_pitch_rate: 0.0_f32,
6523 body_yaw_rate: 0.0_f32,
6524 thrust: 0.0_f32,
6525 target_system: 0_u8,
6526 target_component: 0_u8,
6527 type_mask: AttitudeTargetTypemask::DEFAULT,
6528 thrust_body: [0.0_f32; 3usize],
6529 };
6530 #[cfg(feature = "arbitrary")]
6531 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6532 use arbitrary::{Arbitrary, Unstructured};
6533 let mut buf = [0u8; 1024];
6534 rng.fill_bytes(&mut buf);
6535 let mut unstructured = Unstructured::new(&buf);
6536 Self::arbitrary(&mut unstructured).unwrap_or_default()
6537 }
6538}
6539impl Default for SET_ATTITUDE_TARGET_DATA {
6540 fn default() -> Self {
6541 Self::DEFAULT.clone()
6542 }
6543}
6544impl MessageData for SET_ATTITUDE_TARGET_DATA {
6545 type Message = MavMessage;
6546 const ID: u32 = 82u32;
6547 const NAME: &'static str = "SET_ATTITUDE_TARGET";
6548 const EXTRA_CRC: u8 = 49u8;
6549 const ENCODED_LEN: usize = 51usize;
6550 fn deser(
6551 _version: MavlinkVersion,
6552 __input: &[u8],
6553 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6554 let avail_len = __input.len();
6555 let mut payload_buf = [0; Self::ENCODED_LEN];
6556 let mut buf = if avail_len < Self::ENCODED_LEN {
6557 payload_buf[0..avail_len].copy_from_slice(__input);
6558 Bytes::new(&payload_buf)
6559 } else {
6560 Bytes::new(__input)
6561 };
6562 let mut __struct = Self::default();
6563 __struct.time_boot_ms = buf.get_u32_le();
6564 for v in &mut __struct.q {
6565 let val = buf.get_f32_le();
6566 *v = val;
6567 }
6568 __struct.body_roll_rate = buf.get_f32_le();
6569 __struct.body_pitch_rate = buf.get_f32_le();
6570 __struct.body_yaw_rate = buf.get_f32_le();
6571 __struct.thrust = buf.get_f32_le();
6572 __struct.target_system = buf.get_u8();
6573 __struct.target_component = buf.get_u8();
6574 let tmp = buf.get_u8();
6575 __struct.type_mask = AttitudeTargetTypemask::from_bits(
6576 tmp & AttitudeTargetTypemask::all().bits(),
6577 )
6578 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
6579 flag_type: "AttitudeTargetTypemask",
6580 value: tmp as u32,
6581 })?;
6582 for v in &mut __struct.thrust_body {
6583 let val = buf.get_f32_le();
6584 *v = val;
6585 }
6586 Ok(__struct)
6587 }
6588 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6589 let mut __tmp = BytesMut::new(bytes);
6590 #[allow(clippy::absurd_extreme_comparisons)]
6591 #[allow(unused_comparisons)]
6592 if __tmp.remaining() < Self::ENCODED_LEN {
6593 panic!(
6594 "buffer is too small (need {} bytes, but got {})",
6595 Self::ENCODED_LEN,
6596 __tmp.remaining(),
6597 )
6598 }
6599 __tmp.put_u32_le(self.time_boot_ms);
6600 for val in &self.q {
6601 __tmp.put_f32_le(*val);
6602 }
6603 __tmp.put_f32_le(self.body_roll_rate);
6604 __tmp.put_f32_le(self.body_pitch_rate);
6605 __tmp.put_f32_le(self.body_yaw_rate);
6606 __tmp.put_f32_le(self.thrust);
6607 __tmp.put_u8(self.target_system);
6608 __tmp.put_u8(self.target_component);
6609 __tmp.put_u8(self.type_mask.bits());
6610 for val in &self.thrust_body {
6611 __tmp.put_f32_le(*val);
6612 }
6613 if matches!(version, MavlinkVersion::V2) {
6614 let len = __tmp.len();
6615 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6616 } else {
6617 __tmp.len()
6618 }
6619 }
6620}
6621#[doc = "id: 320"]
6622#[doc = "Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response."]
6623#[derive(Debug, Clone, PartialEq)]
6624#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6625#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6626pub struct PARAM_EXT_REQUEST_READ_DATA {
6627 #[doc = "Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)"]
6628 pub param_index: i16,
6629 #[doc = "System ID"]
6630 pub target_system: u8,
6631 #[doc = "Component ID"]
6632 pub target_component: u8,
6633 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
6634 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6635 pub param_id: [u8; 16],
6636}
6637impl PARAM_EXT_REQUEST_READ_DATA {
6638 pub const ENCODED_LEN: usize = 20usize;
6639 pub const DEFAULT: Self = Self {
6640 param_index: 0_i16,
6641 target_system: 0_u8,
6642 target_component: 0_u8,
6643 param_id: [0_u8; 16usize],
6644 };
6645 #[cfg(feature = "arbitrary")]
6646 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6647 use arbitrary::{Arbitrary, Unstructured};
6648 let mut buf = [0u8; 1024];
6649 rng.fill_bytes(&mut buf);
6650 let mut unstructured = Unstructured::new(&buf);
6651 Self::arbitrary(&mut unstructured).unwrap_or_default()
6652 }
6653}
6654impl Default for PARAM_EXT_REQUEST_READ_DATA {
6655 fn default() -> Self {
6656 Self::DEFAULT.clone()
6657 }
6658}
6659impl MessageData for PARAM_EXT_REQUEST_READ_DATA {
6660 type Message = MavMessage;
6661 const ID: u32 = 320u32;
6662 const NAME: &'static str = "PARAM_EXT_REQUEST_READ";
6663 const EXTRA_CRC: u8 = 243u8;
6664 const ENCODED_LEN: usize = 20usize;
6665 fn deser(
6666 _version: MavlinkVersion,
6667 __input: &[u8],
6668 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6669 let avail_len = __input.len();
6670 let mut payload_buf = [0; Self::ENCODED_LEN];
6671 let mut buf = if avail_len < Self::ENCODED_LEN {
6672 payload_buf[0..avail_len].copy_from_slice(__input);
6673 Bytes::new(&payload_buf)
6674 } else {
6675 Bytes::new(__input)
6676 };
6677 let mut __struct = Self::default();
6678 __struct.param_index = buf.get_i16_le();
6679 __struct.target_system = buf.get_u8();
6680 __struct.target_component = buf.get_u8();
6681 for v in &mut __struct.param_id {
6682 let val = buf.get_u8();
6683 *v = val;
6684 }
6685 Ok(__struct)
6686 }
6687 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6688 let mut __tmp = BytesMut::new(bytes);
6689 #[allow(clippy::absurd_extreme_comparisons)]
6690 #[allow(unused_comparisons)]
6691 if __tmp.remaining() < Self::ENCODED_LEN {
6692 panic!(
6693 "buffer is too small (need {} bytes, but got {})",
6694 Self::ENCODED_LEN,
6695 __tmp.remaining(),
6696 )
6697 }
6698 __tmp.put_i16_le(self.param_index);
6699 __tmp.put_u8(self.target_system);
6700 __tmp.put_u8(self.target_component);
6701 for val in &self.param_id {
6702 __tmp.put_u8(*val);
6703 }
6704 if matches!(version, MavlinkVersion::V2) {
6705 let len = __tmp.len();
6706 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6707 } else {
6708 __tmp.len()
6709 }
6710 }
6711}
6712#[doc = "id: 247"]
6713#[doc = "Information about a potential collision."]
6714#[derive(Debug, Clone, PartialEq)]
6715#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6716#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6717pub struct COLLISION_DATA {
6718 #[doc = "Unique identifier, domain based on src field"]
6719 pub id: u32,
6720 #[doc = "Estimated time until collision occurs"]
6721 pub time_to_minimum_delta: f32,
6722 #[doc = "Closest vertical distance between vehicle and object"]
6723 pub altitude_minimum_delta: f32,
6724 #[doc = "Closest horizontal distance between vehicle and object"]
6725 pub horizontal_minimum_delta: f32,
6726 #[doc = "Collision data source"]
6727 pub src: MavCollisionSrc,
6728 #[doc = "Action that is being taken to avoid this collision"]
6729 pub action: MavCollisionAction,
6730 #[doc = "How concerned the aircraft is about this collision"]
6731 pub threat_level: MavCollisionThreatLevel,
6732}
6733impl COLLISION_DATA {
6734 pub const ENCODED_LEN: usize = 19usize;
6735 pub const DEFAULT: Self = Self {
6736 id: 0_u32,
6737 time_to_minimum_delta: 0.0_f32,
6738 altitude_minimum_delta: 0.0_f32,
6739 horizontal_minimum_delta: 0.0_f32,
6740 src: MavCollisionSrc::DEFAULT,
6741 action: MavCollisionAction::DEFAULT,
6742 threat_level: MavCollisionThreatLevel::DEFAULT,
6743 };
6744 #[cfg(feature = "arbitrary")]
6745 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6746 use arbitrary::{Arbitrary, Unstructured};
6747 let mut buf = [0u8; 1024];
6748 rng.fill_bytes(&mut buf);
6749 let mut unstructured = Unstructured::new(&buf);
6750 Self::arbitrary(&mut unstructured).unwrap_or_default()
6751 }
6752}
6753impl Default for COLLISION_DATA {
6754 fn default() -> Self {
6755 Self::DEFAULT.clone()
6756 }
6757}
6758impl MessageData for COLLISION_DATA {
6759 type Message = MavMessage;
6760 const ID: u32 = 247u32;
6761 const NAME: &'static str = "COLLISION";
6762 const EXTRA_CRC: u8 = 81u8;
6763 const ENCODED_LEN: usize = 19usize;
6764 fn deser(
6765 _version: MavlinkVersion,
6766 __input: &[u8],
6767 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6768 let avail_len = __input.len();
6769 let mut payload_buf = [0; Self::ENCODED_LEN];
6770 let mut buf = if avail_len < Self::ENCODED_LEN {
6771 payload_buf[0..avail_len].copy_from_slice(__input);
6772 Bytes::new(&payload_buf)
6773 } else {
6774 Bytes::new(__input)
6775 };
6776 let mut __struct = Self::default();
6777 __struct.id = buf.get_u32_le();
6778 __struct.time_to_minimum_delta = buf.get_f32_le();
6779 __struct.altitude_minimum_delta = buf.get_f32_le();
6780 __struct.horizontal_minimum_delta = buf.get_f32_le();
6781 let tmp = buf.get_u8();
6782 __struct.src =
6783 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6784 enum_type: "MavCollisionSrc",
6785 value: tmp as u32,
6786 })?;
6787 let tmp = buf.get_u8();
6788 __struct.action =
6789 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6790 enum_type: "MavCollisionAction",
6791 value: tmp as u32,
6792 })?;
6793 let tmp = buf.get_u8();
6794 __struct.threat_level =
6795 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6796 enum_type: "MavCollisionThreatLevel",
6797 value: tmp as u32,
6798 })?;
6799 Ok(__struct)
6800 }
6801 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6802 let mut __tmp = BytesMut::new(bytes);
6803 #[allow(clippy::absurd_extreme_comparisons)]
6804 #[allow(unused_comparisons)]
6805 if __tmp.remaining() < Self::ENCODED_LEN {
6806 panic!(
6807 "buffer is too small (need {} bytes, but got {})",
6808 Self::ENCODED_LEN,
6809 __tmp.remaining(),
6810 )
6811 }
6812 __tmp.put_u32_le(self.id);
6813 __tmp.put_f32_le(self.time_to_minimum_delta);
6814 __tmp.put_f32_le(self.altitude_minimum_delta);
6815 __tmp.put_f32_le(self.horizontal_minimum_delta);
6816 __tmp.put_u8(self.src as u8);
6817 __tmp.put_u8(self.action as u8);
6818 __tmp.put_u8(self.threat_level as u8);
6819 if matches!(version, MavlinkVersion::V2) {
6820 let len = __tmp.len();
6821 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6822 } else {
6823 __tmp.len()
6824 }
6825 }
6826}
6827#[doc = "id: 128"]
6828#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
6829#[derive(Debug, Clone, PartialEq)]
6830#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6831#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6832pub struct GPS2_RTK_DATA {
6833 #[doc = "Time since boot of last baseline message received."]
6834 pub time_last_baseline_ms: u32,
6835 #[doc = "GPS Time of Week of last baseline"]
6836 pub tow: u32,
6837 #[doc = "Current baseline in ECEF x or NED north component."]
6838 pub baseline_a_mm: i32,
6839 #[doc = "Current baseline in ECEF y or NED east component."]
6840 pub baseline_b_mm: i32,
6841 #[doc = "Current baseline in ECEF z or NED down component."]
6842 pub baseline_c_mm: i32,
6843 #[doc = "Current estimate of baseline accuracy."]
6844 pub accuracy: u32,
6845 #[doc = "Current number of integer ambiguity hypotheses."]
6846 pub iar_num_hypotheses: i32,
6847 #[doc = "GPS Week Number of last baseline"]
6848 pub wn: u16,
6849 #[doc = "Identification of connected RTK receiver."]
6850 pub rtk_receiver_id: u8,
6851 #[doc = "GPS-specific health report for RTK data."]
6852 pub rtk_health: u8,
6853 #[doc = "Rate of baseline messages being received by GPS"]
6854 pub rtk_rate: u8,
6855 #[doc = "Current number of sats used for RTK calculation."]
6856 pub nsats: u8,
6857 #[doc = "Coordinate system of baseline"]
6858 pub baseline_coords_type: RtkBaselineCoordinateSystem,
6859}
6860impl GPS2_RTK_DATA {
6861 pub const ENCODED_LEN: usize = 35usize;
6862 pub const DEFAULT: Self = Self {
6863 time_last_baseline_ms: 0_u32,
6864 tow: 0_u32,
6865 baseline_a_mm: 0_i32,
6866 baseline_b_mm: 0_i32,
6867 baseline_c_mm: 0_i32,
6868 accuracy: 0_u32,
6869 iar_num_hypotheses: 0_i32,
6870 wn: 0_u16,
6871 rtk_receiver_id: 0_u8,
6872 rtk_health: 0_u8,
6873 rtk_rate: 0_u8,
6874 nsats: 0_u8,
6875 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
6876 };
6877 #[cfg(feature = "arbitrary")]
6878 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6879 use arbitrary::{Arbitrary, Unstructured};
6880 let mut buf = [0u8; 1024];
6881 rng.fill_bytes(&mut buf);
6882 let mut unstructured = Unstructured::new(&buf);
6883 Self::arbitrary(&mut unstructured).unwrap_or_default()
6884 }
6885}
6886impl Default for GPS2_RTK_DATA {
6887 fn default() -> Self {
6888 Self::DEFAULT.clone()
6889 }
6890}
6891impl MessageData for GPS2_RTK_DATA {
6892 type Message = MavMessage;
6893 const ID: u32 = 128u32;
6894 const NAME: &'static str = "GPS2_RTK";
6895 const EXTRA_CRC: u8 = 226u8;
6896 const ENCODED_LEN: usize = 35usize;
6897 fn deser(
6898 _version: MavlinkVersion,
6899 __input: &[u8],
6900 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6901 let avail_len = __input.len();
6902 let mut payload_buf = [0; Self::ENCODED_LEN];
6903 let mut buf = if avail_len < Self::ENCODED_LEN {
6904 payload_buf[0..avail_len].copy_from_slice(__input);
6905 Bytes::new(&payload_buf)
6906 } else {
6907 Bytes::new(__input)
6908 };
6909 let mut __struct = Self::default();
6910 __struct.time_last_baseline_ms = buf.get_u32_le();
6911 __struct.tow = buf.get_u32_le();
6912 __struct.baseline_a_mm = buf.get_i32_le();
6913 __struct.baseline_b_mm = buf.get_i32_le();
6914 __struct.baseline_c_mm = buf.get_i32_le();
6915 __struct.accuracy = buf.get_u32_le();
6916 __struct.iar_num_hypotheses = buf.get_i32_le();
6917 __struct.wn = buf.get_u16_le();
6918 __struct.rtk_receiver_id = buf.get_u8();
6919 __struct.rtk_health = buf.get_u8();
6920 __struct.rtk_rate = buf.get_u8();
6921 __struct.nsats = buf.get_u8();
6922 let tmp = buf.get_u8();
6923 __struct.baseline_coords_type =
6924 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6925 enum_type: "RtkBaselineCoordinateSystem",
6926 value: tmp as u32,
6927 })?;
6928 Ok(__struct)
6929 }
6930 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6931 let mut __tmp = BytesMut::new(bytes);
6932 #[allow(clippy::absurd_extreme_comparisons)]
6933 #[allow(unused_comparisons)]
6934 if __tmp.remaining() < Self::ENCODED_LEN {
6935 panic!(
6936 "buffer is too small (need {} bytes, but got {})",
6937 Self::ENCODED_LEN,
6938 __tmp.remaining(),
6939 )
6940 }
6941 __tmp.put_u32_le(self.time_last_baseline_ms);
6942 __tmp.put_u32_le(self.tow);
6943 __tmp.put_i32_le(self.baseline_a_mm);
6944 __tmp.put_i32_le(self.baseline_b_mm);
6945 __tmp.put_i32_le(self.baseline_c_mm);
6946 __tmp.put_u32_le(self.accuracy);
6947 __tmp.put_i32_le(self.iar_num_hypotheses);
6948 __tmp.put_u16_le(self.wn);
6949 __tmp.put_u8(self.rtk_receiver_id);
6950 __tmp.put_u8(self.rtk_health);
6951 __tmp.put_u8(self.rtk_rate);
6952 __tmp.put_u8(self.nsats);
6953 __tmp.put_u8(self.baseline_coords_type as u8);
6954 if matches!(version, MavlinkVersion::V2) {
6955 let len = __tmp.len();
6956 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6957 } else {
6958 __tmp.len()
6959 }
6960 }
6961}
6962#[doc = "id: 75"]
6963#[doc = "Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
6964#[derive(Debug, Clone, PartialEq)]
6965#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6966#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6967pub struct COMMAND_INT_DATA {
6968 #[doc = "PARAM1, see MAV_CMD enum"]
6969 pub param1: f32,
6970 #[doc = "PARAM2, see MAV_CMD enum"]
6971 pub param2: f32,
6972 #[doc = "PARAM3, see MAV_CMD enum"]
6973 pub param3: f32,
6974 #[doc = "PARAM4, see MAV_CMD enum"]
6975 pub param4: f32,
6976 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
6977 pub x: i32,
6978 #[doc = "PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7"]
6979 pub y: i32,
6980 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame)."]
6981 pub z: f32,
6982 #[doc = "The scheduled action for the mission item."]
6983 pub command: MavCmd,
6984 #[doc = "System ID"]
6985 pub target_system: u8,
6986 #[doc = "Component ID"]
6987 pub target_component: u8,
6988 #[doc = "The coordinate system of the COMMAND."]
6989 pub frame: MavFrame,
6990 #[doc = "Not used."]
6991 pub current: u8,
6992 #[doc = "Not used (set 0)."]
6993 pub autocontinue: u8,
6994}
6995impl COMMAND_INT_DATA {
6996 pub const ENCODED_LEN: usize = 35usize;
6997 pub const DEFAULT: Self = Self {
6998 param1: 0.0_f32,
6999 param2: 0.0_f32,
7000 param3: 0.0_f32,
7001 param4: 0.0_f32,
7002 x: 0_i32,
7003 y: 0_i32,
7004 z: 0.0_f32,
7005 command: MavCmd::DEFAULT,
7006 target_system: 0_u8,
7007 target_component: 0_u8,
7008 frame: MavFrame::DEFAULT,
7009 current: 0_u8,
7010 autocontinue: 0_u8,
7011 };
7012 #[cfg(feature = "arbitrary")]
7013 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7014 use arbitrary::{Arbitrary, Unstructured};
7015 let mut buf = [0u8; 1024];
7016 rng.fill_bytes(&mut buf);
7017 let mut unstructured = Unstructured::new(&buf);
7018 Self::arbitrary(&mut unstructured).unwrap_or_default()
7019 }
7020}
7021impl Default for COMMAND_INT_DATA {
7022 fn default() -> Self {
7023 Self::DEFAULT.clone()
7024 }
7025}
7026impl MessageData for COMMAND_INT_DATA {
7027 type Message = MavMessage;
7028 const ID: u32 = 75u32;
7029 const NAME: &'static str = "COMMAND_INT";
7030 const EXTRA_CRC: u8 = 158u8;
7031 const ENCODED_LEN: usize = 35usize;
7032 fn deser(
7033 _version: MavlinkVersion,
7034 __input: &[u8],
7035 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7036 let avail_len = __input.len();
7037 let mut payload_buf = [0; Self::ENCODED_LEN];
7038 let mut buf = if avail_len < Self::ENCODED_LEN {
7039 payload_buf[0..avail_len].copy_from_slice(__input);
7040 Bytes::new(&payload_buf)
7041 } else {
7042 Bytes::new(__input)
7043 };
7044 let mut __struct = Self::default();
7045 __struct.param1 = buf.get_f32_le();
7046 __struct.param2 = buf.get_f32_le();
7047 __struct.param3 = buf.get_f32_le();
7048 __struct.param4 = buf.get_f32_le();
7049 __struct.x = buf.get_i32_le();
7050 __struct.y = buf.get_i32_le();
7051 __struct.z = buf.get_f32_le();
7052 let tmp = buf.get_u16_le();
7053 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
7054 ::mavlink_core::error::ParserError::InvalidEnum {
7055 enum_type: "MavCmd",
7056 value: tmp as u32,
7057 },
7058 )?;
7059 __struct.target_system = buf.get_u8();
7060 __struct.target_component = buf.get_u8();
7061 let tmp = buf.get_u8();
7062 __struct.frame =
7063 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7064 enum_type: "MavFrame",
7065 value: tmp as u32,
7066 })?;
7067 __struct.current = buf.get_u8();
7068 __struct.autocontinue = buf.get_u8();
7069 Ok(__struct)
7070 }
7071 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7072 let mut __tmp = BytesMut::new(bytes);
7073 #[allow(clippy::absurd_extreme_comparisons)]
7074 #[allow(unused_comparisons)]
7075 if __tmp.remaining() < Self::ENCODED_LEN {
7076 panic!(
7077 "buffer is too small (need {} bytes, but got {})",
7078 Self::ENCODED_LEN,
7079 __tmp.remaining(),
7080 )
7081 }
7082 __tmp.put_f32_le(self.param1);
7083 __tmp.put_f32_le(self.param2);
7084 __tmp.put_f32_le(self.param3);
7085 __tmp.put_f32_le(self.param4);
7086 __tmp.put_i32_le(self.x);
7087 __tmp.put_i32_le(self.y);
7088 __tmp.put_f32_le(self.z);
7089 __tmp.put_u16_le(self.command as u16);
7090 __tmp.put_u8(self.target_system);
7091 __tmp.put_u8(self.target_component);
7092 __tmp.put_u8(self.frame as u8);
7093 __tmp.put_u8(self.current);
7094 __tmp.put_u8(self.autocontinue);
7095 if matches!(version, MavlinkVersion::V2) {
7096 let len = __tmp.len();
7097 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7098 } else {
7099 __tmp.len()
7100 }
7101 }
7102}
7103#[doc = "id: 12903"]
7104#[doc = "Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation."]
7105#[derive(Debug, Clone, PartialEq)]
7106#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7107#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7108pub struct OPEN_DRONE_ID_SELF_ID_DATA {
7109 #[doc = "System ID (0 for broadcast)."]
7110 pub target_system: u8,
7111 #[doc = "Component ID (0 for broadcast)."]
7112 pub target_component: u8,
7113 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
7114 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7115 pub id_or_mac: [u8; 20],
7116 #[doc = "Indicates the type of the description field."]
7117 pub description_type: MavOdidDescType,
7118 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
7119 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7120 pub description: [u8; 23],
7121}
7122impl OPEN_DRONE_ID_SELF_ID_DATA {
7123 pub const ENCODED_LEN: usize = 46usize;
7124 pub const DEFAULT: Self = Self {
7125 target_system: 0_u8,
7126 target_component: 0_u8,
7127 id_or_mac: [0_u8; 20usize],
7128 description_type: MavOdidDescType::DEFAULT,
7129 description: [0_u8; 23usize],
7130 };
7131 #[cfg(feature = "arbitrary")]
7132 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7133 use arbitrary::{Arbitrary, Unstructured};
7134 let mut buf = [0u8; 1024];
7135 rng.fill_bytes(&mut buf);
7136 let mut unstructured = Unstructured::new(&buf);
7137 Self::arbitrary(&mut unstructured).unwrap_or_default()
7138 }
7139}
7140impl Default for OPEN_DRONE_ID_SELF_ID_DATA {
7141 fn default() -> Self {
7142 Self::DEFAULT.clone()
7143 }
7144}
7145impl MessageData for OPEN_DRONE_ID_SELF_ID_DATA {
7146 type Message = MavMessage;
7147 const ID: u32 = 12903u32;
7148 const NAME: &'static str = "OPEN_DRONE_ID_SELF_ID";
7149 const EXTRA_CRC: u8 = 249u8;
7150 const ENCODED_LEN: usize = 46usize;
7151 fn deser(
7152 _version: MavlinkVersion,
7153 __input: &[u8],
7154 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7155 let avail_len = __input.len();
7156 let mut payload_buf = [0; Self::ENCODED_LEN];
7157 let mut buf = if avail_len < Self::ENCODED_LEN {
7158 payload_buf[0..avail_len].copy_from_slice(__input);
7159 Bytes::new(&payload_buf)
7160 } else {
7161 Bytes::new(__input)
7162 };
7163 let mut __struct = Self::default();
7164 __struct.target_system = buf.get_u8();
7165 __struct.target_component = buf.get_u8();
7166 for v in &mut __struct.id_or_mac {
7167 let val = buf.get_u8();
7168 *v = val;
7169 }
7170 let tmp = buf.get_u8();
7171 __struct.description_type =
7172 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7173 enum_type: "MavOdidDescType",
7174 value: tmp as u32,
7175 })?;
7176 for v in &mut __struct.description {
7177 let val = buf.get_u8();
7178 *v = val;
7179 }
7180 Ok(__struct)
7181 }
7182 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7183 let mut __tmp = BytesMut::new(bytes);
7184 #[allow(clippy::absurd_extreme_comparisons)]
7185 #[allow(unused_comparisons)]
7186 if __tmp.remaining() < Self::ENCODED_LEN {
7187 panic!(
7188 "buffer is too small (need {} bytes, but got {})",
7189 Self::ENCODED_LEN,
7190 __tmp.remaining(),
7191 )
7192 }
7193 __tmp.put_u8(self.target_system);
7194 __tmp.put_u8(self.target_component);
7195 for val in &self.id_or_mac {
7196 __tmp.put_u8(*val);
7197 }
7198 __tmp.put_u8(self.description_type as u8);
7199 for val in &self.description {
7200 __tmp.put_u8(*val);
7201 }
7202 if matches!(version, MavlinkVersion::V2) {
7203 let len = __tmp.len();
7204 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7205 } else {
7206 __tmp.len()
7207 }
7208 }
7209}
7210#[doc = "id: 64"]
7211#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
7212#[derive(Debug, Clone, PartialEq)]
7213#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7214#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7215pub struct LOCAL_POSITION_NED_COV_DATA {
7216 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7217 pub time_usec: u64,
7218 #[doc = "X Position"]
7219 pub x: f32,
7220 #[doc = "Y Position"]
7221 pub y: f32,
7222 #[doc = "Z Position"]
7223 pub z: f32,
7224 #[doc = "X Speed"]
7225 pub vx: f32,
7226 #[doc = "Y Speed"]
7227 pub vy: f32,
7228 #[doc = "Z Speed"]
7229 pub vz: f32,
7230 #[doc = "X Acceleration"]
7231 pub ax: f32,
7232 #[doc = "Y Acceleration"]
7233 pub ay: f32,
7234 #[doc = "Z Acceleration"]
7235 pub az: f32,
7236 #[doc = "Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
7237 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7238 pub covariance: [f32; 45],
7239 #[doc = "Class id of the estimator this estimate originated from."]
7240 pub estimator_type: MavEstimatorType,
7241}
7242impl LOCAL_POSITION_NED_COV_DATA {
7243 pub const ENCODED_LEN: usize = 225usize;
7244 pub const DEFAULT: Self = Self {
7245 time_usec: 0_u64,
7246 x: 0.0_f32,
7247 y: 0.0_f32,
7248 z: 0.0_f32,
7249 vx: 0.0_f32,
7250 vy: 0.0_f32,
7251 vz: 0.0_f32,
7252 ax: 0.0_f32,
7253 ay: 0.0_f32,
7254 az: 0.0_f32,
7255 covariance: [0.0_f32; 45usize],
7256 estimator_type: MavEstimatorType::DEFAULT,
7257 };
7258 #[cfg(feature = "arbitrary")]
7259 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7260 use arbitrary::{Arbitrary, Unstructured};
7261 let mut buf = [0u8; 1024];
7262 rng.fill_bytes(&mut buf);
7263 let mut unstructured = Unstructured::new(&buf);
7264 Self::arbitrary(&mut unstructured).unwrap_or_default()
7265 }
7266}
7267impl Default for LOCAL_POSITION_NED_COV_DATA {
7268 fn default() -> Self {
7269 Self::DEFAULT.clone()
7270 }
7271}
7272impl MessageData for LOCAL_POSITION_NED_COV_DATA {
7273 type Message = MavMessage;
7274 const ID: u32 = 64u32;
7275 const NAME: &'static str = "LOCAL_POSITION_NED_COV";
7276 const EXTRA_CRC: u8 = 191u8;
7277 const ENCODED_LEN: usize = 225usize;
7278 fn deser(
7279 _version: MavlinkVersion,
7280 __input: &[u8],
7281 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7282 let avail_len = __input.len();
7283 let mut payload_buf = [0; Self::ENCODED_LEN];
7284 let mut buf = if avail_len < Self::ENCODED_LEN {
7285 payload_buf[0..avail_len].copy_from_slice(__input);
7286 Bytes::new(&payload_buf)
7287 } else {
7288 Bytes::new(__input)
7289 };
7290 let mut __struct = Self::default();
7291 __struct.time_usec = buf.get_u64_le();
7292 __struct.x = buf.get_f32_le();
7293 __struct.y = buf.get_f32_le();
7294 __struct.z = buf.get_f32_le();
7295 __struct.vx = buf.get_f32_le();
7296 __struct.vy = buf.get_f32_le();
7297 __struct.vz = buf.get_f32_le();
7298 __struct.ax = buf.get_f32_le();
7299 __struct.ay = buf.get_f32_le();
7300 __struct.az = buf.get_f32_le();
7301 for v in &mut __struct.covariance {
7302 let val = buf.get_f32_le();
7303 *v = val;
7304 }
7305 let tmp = buf.get_u8();
7306 __struct.estimator_type =
7307 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7308 enum_type: "MavEstimatorType",
7309 value: tmp as u32,
7310 })?;
7311 Ok(__struct)
7312 }
7313 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7314 let mut __tmp = BytesMut::new(bytes);
7315 #[allow(clippy::absurd_extreme_comparisons)]
7316 #[allow(unused_comparisons)]
7317 if __tmp.remaining() < Self::ENCODED_LEN {
7318 panic!(
7319 "buffer is too small (need {} bytes, but got {})",
7320 Self::ENCODED_LEN,
7321 __tmp.remaining(),
7322 )
7323 }
7324 __tmp.put_u64_le(self.time_usec);
7325 __tmp.put_f32_le(self.x);
7326 __tmp.put_f32_le(self.y);
7327 __tmp.put_f32_le(self.z);
7328 __tmp.put_f32_le(self.vx);
7329 __tmp.put_f32_le(self.vy);
7330 __tmp.put_f32_le(self.vz);
7331 __tmp.put_f32_le(self.ax);
7332 __tmp.put_f32_le(self.ay);
7333 __tmp.put_f32_le(self.az);
7334 for val in &self.covariance {
7335 __tmp.put_f32_le(*val);
7336 }
7337 __tmp.put_u8(self.estimator_type as u8);
7338 if matches!(version, MavlinkVersion::V2) {
7339 let len = __tmp.len();
7340 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7341 } else {
7342 __tmp.len()
7343 }
7344 }
7345}
7346#[doc = "id: 107"]
7347#[doc = "The IMU readings in SI units in NED body frame."]
7348#[derive(Debug, Clone, PartialEq)]
7349#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7350#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7351pub struct HIL_SENSOR_DATA {
7352 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7353 pub time_usec: u64,
7354 #[doc = "X acceleration"]
7355 pub xacc: f32,
7356 #[doc = "Y acceleration"]
7357 pub yacc: f32,
7358 #[doc = "Z acceleration"]
7359 pub zacc: f32,
7360 #[doc = "Angular speed around X axis in body frame"]
7361 pub xgyro: f32,
7362 #[doc = "Angular speed around Y axis in body frame"]
7363 pub ygyro: f32,
7364 #[doc = "Angular speed around Z axis in body frame"]
7365 pub zgyro: f32,
7366 #[doc = "X Magnetic field"]
7367 pub xmag: f32,
7368 #[doc = "Y Magnetic field"]
7369 pub ymag: f32,
7370 #[doc = "Z Magnetic field"]
7371 pub zmag: f32,
7372 #[doc = "Absolute pressure"]
7373 pub abs_pressure: f32,
7374 #[doc = "Differential pressure (airspeed)"]
7375 pub diff_pressure: f32,
7376 #[doc = "Altitude calculated from pressure"]
7377 pub pressure_alt: f32,
7378 #[doc = "Temperature"]
7379 pub temperature: f32,
7380 #[doc = "Bitmap for fields that have updated since last message"]
7381 pub fields_updated: HilSensorUpdatedFlags,
7382 #[doc = "Sensor ID (zero indexed). Used for multiple sensor inputs"]
7383 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7384 pub id: u8,
7385}
7386impl HIL_SENSOR_DATA {
7387 pub const ENCODED_LEN: usize = 65usize;
7388 pub const DEFAULT: Self = Self {
7389 time_usec: 0_u64,
7390 xacc: 0.0_f32,
7391 yacc: 0.0_f32,
7392 zacc: 0.0_f32,
7393 xgyro: 0.0_f32,
7394 ygyro: 0.0_f32,
7395 zgyro: 0.0_f32,
7396 xmag: 0.0_f32,
7397 ymag: 0.0_f32,
7398 zmag: 0.0_f32,
7399 abs_pressure: 0.0_f32,
7400 diff_pressure: 0.0_f32,
7401 pressure_alt: 0.0_f32,
7402 temperature: 0.0_f32,
7403 fields_updated: HilSensorUpdatedFlags::DEFAULT,
7404 id: 0_u8,
7405 };
7406 #[cfg(feature = "arbitrary")]
7407 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7408 use arbitrary::{Arbitrary, Unstructured};
7409 let mut buf = [0u8; 1024];
7410 rng.fill_bytes(&mut buf);
7411 let mut unstructured = Unstructured::new(&buf);
7412 Self::arbitrary(&mut unstructured).unwrap_or_default()
7413 }
7414}
7415impl Default for HIL_SENSOR_DATA {
7416 fn default() -> Self {
7417 Self::DEFAULT.clone()
7418 }
7419}
7420impl MessageData for HIL_SENSOR_DATA {
7421 type Message = MavMessage;
7422 const ID: u32 = 107u32;
7423 const NAME: &'static str = "HIL_SENSOR";
7424 const EXTRA_CRC: u8 = 108u8;
7425 const ENCODED_LEN: usize = 65usize;
7426 fn deser(
7427 _version: MavlinkVersion,
7428 __input: &[u8],
7429 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7430 let avail_len = __input.len();
7431 let mut payload_buf = [0; Self::ENCODED_LEN];
7432 let mut buf = if avail_len < Self::ENCODED_LEN {
7433 payload_buf[0..avail_len].copy_from_slice(__input);
7434 Bytes::new(&payload_buf)
7435 } else {
7436 Bytes::new(__input)
7437 };
7438 let mut __struct = Self::default();
7439 __struct.time_usec = buf.get_u64_le();
7440 __struct.xacc = buf.get_f32_le();
7441 __struct.yacc = buf.get_f32_le();
7442 __struct.zacc = buf.get_f32_le();
7443 __struct.xgyro = buf.get_f32_le();
7444 __struct.ygyro = buf.get_f32_le();
7445 __struct.zgyro = buf.get_f32_le();
7446 __struct.xmag = buf.get_f32_le();
7447 __struct.ymag = buf.get_f32_le();
7448 __struct.zmag = buf.get_f32_le();
7449 __struct.abs_pressure = buf.get_f32_le();
7450 __struct.diff_pressure = buf.get_f32_le();
7451 __struct.pressure_alt = buf.get_f32_le();
7452 __struct.temperature = buf.get_f32_le();
7453 let tmp = buf.get_u32_le();
7454 __struct.fields_updated = HilSensorUpdatedFlags::from_bits(
7455 tmp & HilSensorUpdatedFlags::all().bits(),
7456 )
7457 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
7458 flag_type: "HilSensorUpdatedFlags",
7459 value: tmp as u32,
7460 })?;
7461 __struct.id = buf.get_u8();
7462 Ok(__struct)
7463 }
7464 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7465 let mut __tmp = BytesMut::new(bytes);
7466 #[allow(clippy::absurd_extreme_comparisons)]
7467 #[allow(unused_comparisons)]
7468 if __tmp.remaining() < Self::ENCODED_LEN {
7469 panic!(
7470 "buffer is too small (need {} bytes, but got {})",
7471 Self::ENCODED_LEN,
7472 __tmp.remaining(),
7473 )
7474 }
7475 __tmp.put_u64_le(self.time_usec);
7476 __tmp.put_f32_le(self.xacc);
7477 __tmp.put_f32_le(self.yacc);
7478 __tmp.put_f32_le(self.zacc);
7479 __tmp.put_f32_le(self.xgyro);
7480 __tmp.put_f32_le(self.ygyro);
7481 __tmp.put_f32_le(self.zgyro);
7482 __tmp.put_f32_le(self.xmag);
7483 __tmp.put_f32_le(self.ymag);
7484 __tmp.put_f32_le(self.zmag);
7485 __tmp.put_f32_le(self.abs_pressure);
7486 __tmp.put_f32_le(self.diff_pressure);
7487 __tmp.put_f32_le(self.pressure_alt);
7488 __tmp.put_f32_le(self.temperature);
7489 __tmp.put_u32_le(self.fields_updated.bits());
7490 __tmp.put_u8(self.id);
7491 if matches!(version, MavlinkVersion::V2) {
7492 let len = __tmp.len();
7493 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7494 } else {
7495 __tmp.len()
7496 }
7497 }
7498}
7499#[doc = "id: 11"]
7500#[doc = "Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component."]
7501#[derive(Debug, Clone, PartialEq)]
7502#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7503#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7504pub struct SET_MODE_DATA {
7505 #[doc = "The new autopilot-specific mode. This field can be ignored by an autopilot."]
7506 pub custom_mode: u32,
7507 #[doc = "The system setting the mode"]
7508 pub target_system: u8,
7509 #[doc = "The new base mode."]
7510 pub base_mode: MavMode,
7511}
7512impl SET_MODE_DATA {
7513 pub const ENCODED_LEN: usize = 6usize;
7514 pub const DEFAULT: Self = Self {
7515 custom_mode: 0_u32,
7516 target_system: 0_u8,
7517 base_mode: MavMode::DEFAULT,
7518 };
7519 #[cfg(feature = "arbitrary")]
7520 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7521 use arbitrary::{Arbitrary, Unstructured};
7522 let mut buf = [0u8; 1024];
7523 rng.fill_bytes(&mut buf);
7524 let mut unstructured = Unstructured::new(&buf);
7525 Self::arbitrary(&mut unstructured).unwrap_or_default()
7526 }
7527}
7528impl Default for SET_MODE_DATA {
7529 fn default() -> Self {
7530 Self::DEFAULT.clone()
7531 }
7532}
7533impl MessageData for SET_MODE_DATA {
7534 type Message = MavMessage;
7535 const ID: u32 = 11u32;
7536 const NAME: &'static str = "SET_MODE";
7537 const EXTRA_CRC: u8 = 89u8;
7538 const ENCODED_LEN: usize = 6usize;
7539 fn deser(
7540 _version: MavlinkVersion,
7541 __input: &[u8],
7542 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7543 let avail_len = __input.len();
7544 let mut payload_buf = [0; Self::ENCODED_LEN];
7545 let mut buf = if avail_len < Self::ENCODED_LEN {
7546 payload_buf[0..avail_len].copy_from_slice(__input);
7547 Bytes::new(&payload_buf)
7548 } else {
7549 Bytes::new(__input)
7550 };
7551 let mut __struct = Self::default();
7552 __struct.custom_mode = buf.get_u32_le();
7553 __struct.target_system = buf.get_u8();
7554 let tmp = buf.get_u8();
7555 __struct.base_mode =
7556 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7557 enum_type: "MavMode",
7558 value: tmp as u32,
7559 })?;
7560 Ok(__struct)
7561 }
7562 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7563 let mut __tmp = BytesMut::new(bytes);
7564 #[allow(clippy::absurd_extreme_comparisons)]
7565 #[allow(unused_comparisons)]
7566 if __tmp.remaining() < Self::ENCODED_LEN {
7567 panic!(
7568 "buffer is too small (need {} bytes, but got {})",
7569 Self::ENCODED_LEN,
7570 __tmp.remaining(),
7571 )
7572 }
7573 __tmp.put_u32_le(self.custom_mode);
7574 __tmp.put_u8(self.target_system);
7575 __tmp.put_u8(self.base_mode as u8);
7576 if matches!(version, MavlinkVersion::V2) {
7577 let len = __tmp.len();
7578 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7579 } else {
7580 __tmp.len()
7581 }
7582 }
7583}
7584#[doc = "id: 28"]
7585#[doc = "The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values."]
7586#[derive(Debug, Clone, PartialEq)]
7587#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7588#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7589pub struct RAW_PRESSURE_DATA {
7590 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7591 pub time_usec: u64,
7592 #[doc = "Absolute pressure (raw)"]
7593 pub press_abs: i16,
7594 #[doc = "Differential pressure 1 (raw, 0 if nonexistent)"]
7595 pub press_diff1: i16,
7596 #[doc = "Differential pressure 2 (raw, 0 if nonexistent)"]
7597 pub press_diff2: i16,
7598 #[doc = "Raw Temperature measurement (raw)"]
7599 pub temperature: i16,
7600}
7601impl RAW_PRESSURE_DATA {
7602 pub const ENCODED_LEN: usize = 16usize;
7603 pub const DEFAULT: Self = Self {
7604 time_usec: 0_u64,
7605 press_abs: 0_i16,
7606 press_diff1: 0_i16,
7607 press_diff2: 0_i16,
7608 temperature: 0_i16,
7609 };
7610 #[cfg(feature = "arbitrary")]
7611 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7612 use arbitrary::{Arbitrary, Unstructured};
7613 let mut buf = [0u8; 1024];
7614 rng.fill_bytes(&mut buf);
7615 let mut unstructured = Unstructured::new(&buf);
7616 Self::arbitrary(&mut unstructured).unwrap_or_default()
7617 }
7618}
7619impl Default for RAW_PRESSURE_DATA {
7620 fn default() -> Self {
7621 Self::DEFAULT.clone()
7622 }
7623}
7624impl MessageData for RAW_PRESSURE_DATA {
7625 type Message = MavMessage;
7626 const ID: u32 = 28u32;
7627 const NAME: &'static str = "RAW_PRESSURE";
7628 const EXTRA_CRC: u8 = 67u8;
7629 const ENCODED_LEN: usize = 16usize;
7630 fn deser(
7631 _version: MavlinkVersion,
7632 __input: &[u8],
7633 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7634 let avail_len = __input.len();
7635 let mut payload_buf = [0; Self::ENCODED_LEN];
7636 let mut buf = if avail_len < Self::ENCODED_LEN {
7637 payload_buf[0..avail_len].copy_from_slice(__input);
7638 Bytes::new(&payload_buf)
7639 } else {
7640 Bytes::new(__input)
7641 };
7642 let mut __struct = Self::default();
7643 __struct.time_usec = buf.get_u64_le();
7644 __struct.press_abs = buf.get_i16_le();
7645 __struct.press_diff1 = buf.get_i16_le();
7646 __struct.press_diff2 = buf.get_i16_le();
7647 __struct.temperature = buf.get_i16_le();
7648 Ok(__struct)
7649 }
7650 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7651 let mut __tmp = BytesMut::new(bytes);
7652 #[allow(clippy::absurd_extreme_comparisons)]
7653 #[allow(unused_comparisons)]
7654 if __tmp.remaining() < Self::ENCODED_LEN {
7655 panic!(
7656 "buffer is too small (need {} bytes, but got {})",
7657 Self::ENCODED_LEN,
7658 __tmp.remaining(),
7659 )
7660 }
7661 __tmp.put_u64_le(self.time_usec);
7662 __tmp.put_i16_le(self.press_abs);
7663 __tmp.put_i16_le(self.press_diff1);
7664 __tmp.put_i16_le(self.press_diff2);
7665 __tmp.put_i16_le(self.temperature);
7666 if matches!(version, MavlinkVersion::V2) {
7667 let len = __tmp.len();
7668 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7669 } else {
7670 __tmp.len()
7671 }
7672 }
7673}
7674#[doc = "id: 111"]
7675#[doc = "Time synchronization message. The message is used for both timesync requests and responses. The request is sent with `ts1=syncing component timestamp` and `tc1=0`, and may be broadcast or targeted to a specific system/component. The response is sent with `ts1=syncing component timestamp` (mirror back unchanged), and `tc1=responding component timestamp`, with the `target_system` and `target_component` set to ids of the original request. Systems can determine if they are receiving a request or response based on the value of `tc`. If the response has `target_system==target_component==0` the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used). The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset. See also: <https://mavlink.io/en/services/timesync.html>."]
7676#[derive(Debug, Clone, PartialEq)]
7677#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7678#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7679pub struct TIMESYNC_DATA {
7680 #[doc = "Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component."]
7681 pub tc1: i64,
7682 #[doc = "Time sync timestamp 2. Timestamp of syncing component (mirrored in response)."]
7683 pub ts1: i64,
7684 #[doc = "Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component."]
7685 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7686 pub target_system: u8,
7687 #[doc = "Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component."]
7688 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7689 pub target_component: u8,
7690}
7691impl TIMESYNC_DATA {
7692 pub const ENCODED_LEN: usize = 18usize;
7693 pub const DEFAULT: Self = Self {
7694 tc1: 0_i64,
7695 ts1: 0_i64,
7696 target_system: 0_u8,
7697 target_component: 0_u8,
7698 };
7699 #[cfg(feature = "arbitrary")]
7700 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7701 use arbitrary::{Arbitrary, Unstructured};
7702 let mut buf = [0u8; 1024];
7703 rng.fill_bytes(&mut buf);
7704 let mut unstructured = Unstructured::new(&buf);
7705 Self::arbitrary(&mut unstructured).unwrap_or_default()
7706 }
7707}
7708impl Default for TIMESYNC_DATA {
7709 fn default() -> Self {
7710 Self::DEFAULT.clone()
7711 }
7712}
7713impl MessageData for TIMESYNC_DATA {
7714 type Message = MavMessage;
7715 const ID: u32 = 111u32;
7716 const NAME: &'static str = "TIMESYNC";
7717 const EXTRA_CRC: u8 = 34u8;
7718 const ENCODED_LEN: usize = 18usize;
7719 fn deser(
7720 _version: MavlinkVersion,
7721 __input: &[u8],
7722 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7723 let avail_len = __input.len();
7724 let mut payload_buf = [0; Self::ENCODED_LEN];
7725 let mut buf = if avail_len < Self::ENCODED_LEN {
7726 payload_buf[0..avail_len].copy_from_slice(__input);
7727 Bytes::new(&payload_buf)
7728 } else {
7729 Bytes::new(__input)
7730 };
7731 let mut __struct = Self::default();
7732 __struct.tc1 = buf.get_i64_le();
7733 __struct.ts1 = buf.get_i64_le();
7734 __struct.target_system = buf.get_u8();
7735 __struct.target_component = buf.get_u8();
7736 Ok(__struct)
7737 }
7738 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7739 let mut __tmp = BytesMut::new(bytes);
7740 #[allow(clippy::absurd_extreme_comparisons)]
7741 #[allow(unused_comparisons)]
7742 if __tmp.remaining() < Self::ENCODED_LEN {
7743 panic!(
7744 "buffer is too small (need {} bytes, but got {})",
7745 Self::ENCODED_LEN,
7746 __tmp.remaining(),
7747 )
7748 }
7749 __tmp.put_i64_le(self.tc1);
7750 __tmp.put_i64_le(self.ts1);
7751 __tmp.put_u8(self.target_system);
7752 __tmp.put_u8(self.target_component);
7753 if matches!(version, MavlinkVersion::V2) {
7754 let len = __tmp.len();
7755 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7756 } else {
7757 __tmp.len()
7758 }
7759 }
7760}
7761#[doc = "id: 66"]
7762#[doc = "Request a data stream."]
7763#[derive(Debug, Clone, PartialEq)]
7764#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7765#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7766pub struct REQUEST_DATA_STREAM_DATA {
7767 #[doc = "The requested message rate"]
7768 pub req_message_rate: u16,
7769 #[doc = "The target requested to send the message stream."]
7770 pub target_system: u8,
7771 #[doc = "The target requested to send the message stream."]
7772 pub target_component: u8,
7773 #[doc = "The ID of the requested data stream"]
7774 pub req_stream_id: u8,
7775 #[doc = "1 to start sending, 0 to stop sending."]
7776 pub start_stop: u8,
7777}
7778impl REQUEST_DATA_STREAM_DATA {
7779 pub const ENCODED_LEN: usize = 6usize;
7780 pub const DEFAULT: Self = Self {
7781 req_message_rate: 0_u16,
7782 target_system: 0_u8,
7783 target_component: 0_u8,
7784 req_stream_id: 0_u8,
7785 start_stop: 0_u8,
7786 };
7787 #[cfg(feature = "arbitrary")]
7788 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7789 use arbitrary::{Arbitrary, Unstructured};
7790 let mut buf = [0u8; 1024];
7791 rng.fill_bytes(&mut buf);
7792 let mut unstructured = Unstructured::new(&buf);
7793 Self::arbitrary(&mut unstructured).unwrap_or_default()
7794 }
7795}
7796impl Default for REQUEST_DATA_STREAM_DATA {
7797 fn default() -> Self {
7798 Self::DEFAULT.clone()
7799 }
7800}
7801impl MessageData for REQUEST_DATA_STREAM_DATA {
7802 type Message = MavMessage;
7803 const ID: u32 = 66u32;
7804 const NAME: &'static str = "REQUEST_DATA_STREAM";
7805 const EXTRA_CRC: u8 = 148u8;
7806 const ENCODED_LEN: usize = 6usize;
7807 fn deser(
7808 _version: MavlinkVersion,
7809 __input: &[u8],
7810 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7811 let avail_len = __input.len();
7812 let mut payload_buf = [0; Self::ENCODED_LEN];
7813 let mut buf = if avail_len < Self::ENCODED_LEN {
7814 payload_buf[0..avail_len].copy_from_slice(__input);
7815 Bytes::new(&payload_buf)
7816 } else {
7817 Bytes::new(__input)
7818 };
7819 let mut __struct = Self::default();
7820 __struct.req_message_rate = buf.get_u16_le();
7821 __struct.target_system = buf.get_u8();
7822 __struct.target_component = buf.get_u8();
7823 __struct.req_stream_id = buf.get_u8();
7824 __struct.start_stop = buf.get_u8();
7825 Ok(__struct)
7826 }
7827 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7828 let mut __tmp = BytesMut::new(bytes);
7829 #[allow(clippy::absurd_extreme_comparisons)]
7830 #[allow(unused_comparisons)]
7831 if __tmp.remaining() < Self::ENCODED_LEN {
7832 panic!(
7833 "buffer is too small (need {} bytes, but got {})",
7834 Self::ENCODED_LEN,
7835 __tmp.remaining(),
7836 )
7837 }
7838 __tmp.put_u16_le(self.req_message_rate);
7839 __tmp.put_u8(self.target_system);
7840 __tmp.put_u8(self.target_component);
7841 __tmp.put_u8(self.req_stream_id);
7842 __tmp.put_u8(self.start_stop);
7843 if matches!(version, MavlinkVersion::V2) {
7844 let len = __tmp.len();
7845 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7846 } else {
7847 __tmp.len()
7848 }
7849 }
7850}
7851#[doc = "id: 113"]
7852#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
7853#[derive(Debug, Clone, PartialEq)]
7854#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7855#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7856pub struct HIL_GPS_DATA {
7857 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7858 pub time_usec: u64,
7859 #[doc = "Latitude (WGS84)"]
7860 pub lat: i32,
7861 #[doc = "Longitude (WGS84)"]
7862 pub lon: i32,
7863 #[doc = "Altitude (MSL). Positive for up."]
7864 pub alt: i32,
7865 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
7866 pub eph: u16,
7867 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
7868 pub epv: u16,
7869 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
7870 pub vel: u16,
7871 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
7872 pub vn: i16,
7873 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
7874 pub ve: i16,
7875 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
7876 pub vd: i16,
7877 #[doc = "Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
7878 pub cog: u16,
7879 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix."]
7880 pub fix_type: u8,
7881 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
7882 pub satellites_visible: u8,
7883 #[doc = "GPS ID (zero indexed). Used for multiple GPS inputs"]
7884 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7885 pub id: u8,
7886 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
7887 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7888 pub yaw: u16,
7889}
7890impl HIL_GPS_DATA {
7891 pub const ENCODED_LEN: usize = 39usize;
7892 pub const DEFAULT: Self = Self {
7893 time_usec: 0_u64,
7894 lat: 0_i32,
7895 lon: 0_i32,
7896 alt: 0_i32,
7897 eph: 0_u16,
7898 epv: 0_u16,
7899 vel: 0_u16,
7900 vn: 0_i16,
7901 ve: 0_i16,
7902 vd: 0_i16,
7903 cog: 0_u16,
7904 fix_type: 0_u8,
7905 satellites_visible: 0_u8,
7906 id: 0_u8,
7907 yaw: 0_u16,
7908 };
7909 #[cfg(feature = "arbitrary")]
7910 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7911 use arbitrary::{Arbitrary, Unstructured};
7912 let mut buf = [0u8; 1024];
7913 rng.fill_bytes(&mut buf);
7914 let mut unstructured = Unstructured::new(&buf);
7915 Self::arbitrary(&mut unstructured).unwrap_or_default()
7916 }
7917}
7918impl Default for HIL_GPS_DATA {
7919 fn default() -> Self {
7920 Self::DEFAULT.clone()
7921 }
7922}
7923impl MessageData for HIL_GPS_DATA {
7924 type Message = MavMessage;
7925 const ID: u32 = 113u32;
7926 const NAME: &'static str = "HIL_GPS";
7927 const EXTRA_CRC: u8 = 124u8;
7928 const ENCODED_LEN: usize = 39usize;
7929 fn deser(
7930 _version: MavlinkVersion,
7931 __input: &[u8],
7932 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7933 let avail_len = __input.len();
7934 let mut payload_buf = [0; Self::ENCODED_LEN];
7935 let mut buf = if avail_len < Self::ENCODED_LEN {
7936 payload_buf[0..avail_len].copy_from_slice(__input);
7937 Bytes::new(&payload_buf)
7938 } else {
7939 Bytes::new(__input)
7940 };
7941 let mut __struct = Self::default();
7942 __struct.time_usec = buf.get_u64_le();
7943 __struct.lat = buf.get_i32_le();
7944 __struct.lon = buf.get_i32_le();
7945 __struct.alt = buf.get_i32_le();
7946 __struct.eph = buf.get_u16_le();
7947 __struct.epv = buf.get_u16_le();
7948 __struct.vel = buf.get_u16_le();
7949 __struct.vn = buf.get_i16_le();
7950 __struct.ve = buf.get_i16_le();
7951 __struct.vd = buf.get_i16_le();
7952 __struct.cog = buf.get_u16_le();
7953 __struct.fix_type = buf.get_u8();
7954 __struct.satellites_visible = buf.get_u8();
7955 __struct.id = buf.get_u8();
7956 __struct.yaw = buf.get_u16_le();
7957 Ok(__struct)
7958 }
7959 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7960 let mut __tmp = BytesMut::new(bytes);
7961 #[allow(clippy::absurd_extreme_comparisons)]
7962 #[allow(unused_comparisons)]
7963 if __tmp.remaining() < Self::ENCODED_LEN {
7964 panic!(
7965 "buffer is too small (need {} bytes, but got {})",
7966 Self::ENCODED_LEN,
7967 __tmp.remaining(),
7968 )
7969 }
7970 __tmp.put_u64_le(self.time_usec);
7971 __tmp.put_i32_le(self.lat);
7972 __tmp.put_i32_le(self.lon);
7973 __tmp.put_i32_le(self.alt);
7974 __tmp.put_u16_le(self.eph);
7975 __tmp.put_u16_le(self.epv);
7976 __tmp.put_u16_le(self.vel);
7977 __tmp.put_i16_le(self.vn);
7978 __tmp.put_i16_le(self.ve);
7979 __tmp.put_i16_le(self.vd);
7980 __tmp.put_u16_le(self.cog);
7981 __tmp.put_u8(self.fix_type);
7982 __tmp.put_u8(self.satellites_visible);
7983 __tmp.put_u8(self.id);
7984 __tmp.put_u16_le(self.yaw);
7985 if matches!(version, MavlinkVersion::V2) {
7986 let len = __tmp.len();
7987 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7988 } else {
7989 __tmp.len()
7990 }
7991 }
7992}
7993#[doc = "id: 386"]
7994#[doc = "A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD."]
7995#[derive(Debug, Clone, PartialEq)]
7996#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7997#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7998pub struct CAN_FRAME_DATA {
7999 #[doc = "Frame ID"]
8000 pub id: u32,
8001 #[doc = "System ID."]
8002 pub target_system: u8,
8003 #[doc = "Component ID."]
8004 pub target_component: u8,
8005 #[doc = "Bus number"]
8006 pub bus: u8,
8007 #[doc = "Frame length"]
8008 pub len: u8,
8009 #[doc = "Frame data"]
8010 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8011 pub data: [u8; 8],
8012}
8013impl CAN_FRAME_DATA {
8014 pub const ENCODED_LEN: usize = 16usize;
8015 pub const DEFAULT: Self = Self {
8016 id: 0_u32,
8017 target_system: 0_u8,
8018 target_component: 0_u8,
8019 bus: 0_u8,
8020 len: 0_u8,
8021 data: [0_u8; 8usize],
8022 };
8023 #[cfg(feature = "arbitrary")]
8024 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8025 use arbitrary::{Arbitrary, Unstructured};
8026 let mut buf = [0u8; 1024];
8027 rng.fill_bytes(&mut buf);
8028 let mut unstructured = Unstructured::new(&buf);
8029 Self::arbitrary(&mut unstructured).unwrap_or_default()
8030 }
8031}
8032impl Default for CAN_FRAME_DATA {
8033 fn default() -> Self {
8034 Self::DEFAULT.clone()
8035 }
8036}
8037impl MessageData for CAN_FRAME_DATA {
8038 type Message = MavMessage;
8039 const ID: u32 = 386u32;
8040 const NAME: &'static str = "CAN_FRAME";
8041 const EXTRA_CRC: u8 = 132u8;
8042 const ENCODED_LEN: usize = 16usize;
8043 fn deser(
8044 _version: MavlinkVersion,
8045 __input: &[u8],
8046 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8047 let avail_len = __input.len();
8048 let mut payload_buf = [0; Self::ENCODED_LEN];
8049 let mut buf = if avail_len < Self::ENCODED_LEN {
8050 payload_buf[0..avail_len].copy_from_slice(__input);
8051 Bytes::new(&payload_buf)
8052 } else {
8053 Bytes::new(__input)
8054 };
8055 let mut __struct = Self::default();
8056 __struct.id = buf.get_u32_le();
8057 __struct.target_system = buf.get_u8();
8058 __struct.target_component = buf.get_u8();
8059 __struct.bus = buf.get_u8();
8060 __struct.len = buf.get_u8();
8061 for v in &mut __struct.data {
8062 let val = buf.get_u8();
8063 *v = val;
8064 }
8065 Ok(__struct)
8066 }
8067 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8068 let mut __tmp = BytesMut::new(bytes);
8069 #[allow(clippy::absurd_extreme_comparisons)]
8070 #[allow(unused_comparisons)]
8071 if __tmp.remaining() < Self::ENCODED_LEN {
8072 panic!(
8073 "buffer is too small (need {} bytes, but got {})",
8074 Self::ENCODED_LEN,
8075 __tmp.remaining(),
8076 )
8077 }
8078 __tmp.put_u32_le(self.id);
8079 __tmp.put_u8(self.target_system);
8080 __tmp.put_u8(self.target_component);
8081 __tmp.put_u8(self.bus);
8082 __tmp.put_u8(self.len);
8083 for val in &self.data {
8084 __tmp.put_u8(*val);
8085 }
8086 if matches!(version, MavlinkVersion::V2) {
8087 let len = __tmp.len();
8088 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8089 } else {
8090 __tmp.len()
8091 }
8092 }
8093}
8094#[doc = "id: 12920"]
8095#[doc = "Temperature and humidity from hygrometer."]
8096#[derive(Debug, Clone, PartialEq)]
8097#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8098#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8099pub struct HYGROMETER_SENSOR_DATA {
8100 #[doc = "Temperature"]
8101 pub temperature: i16,
8102 #[doc = "Humidity"]
8103 pub humidity: u16,
8104 #[doc = "Hygrometer ID"]
8105 pub id: u8,
8106}
8107impl HYGROMETER_SENSOR_DATA {
8108 pub const ENCODED_LEN: usize = 5usize;
8109 pub const DEFAULT: Self = Self {
8110 temperature: 0_i16,
8111 humidity: 0_u16,
8112 id: 0_u8,
8113 };
8114 #[cfg(feature = "arbitrary")]
8115 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8116 use arbitrary::{Arbitrary, Unstructured};
8117 let mut buf = [0u8; 1024];
8118 rng.fill_bytes(&mut buf);
8119 let mut unstructured = Unstructured::new(&buf);
8120 Self::arbitrary(&mut unstructured).unwrap_or_default()
8121 }
8122}
8123impl Default for HYGROMETER_SENSOR_DATA {
8124 fn default() -> Self {
8125 Self::DEFAULT.clone()
8126 }
8127}
8128impl MessageData for HYGROMETER_SENSOR_DATA {
8129 type Message = MavMessage;
8130 const ID: u32 = 12920u32;
8131 const NAME: &'static str = "HYGROMETER_SENSOR";
8132 const EXTRA_CRC: u8 = 20u8;
8133 const ENCODED_LEN: usize = 5usize;
8134 fn deser(
8135 _version: MavlinkVersion,
8136 __input: &[u8],
8137 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8138 let avail_len = __input.len();
8139 let mut payload_buf = [0; Self::ENCODED_LEN];
8140 let mut buf = if avail_len < Self::ENCODED_LEN {
8141 payload_buf[0..avail_len].copy_from_slice(__input);
8142 Bytes::new(&payload_buf)
8143 } else {
8144 Bytes::new(__input)
8145 };
8146 let mut __struct = Self::default();
8147 __struct.temperature = buf.get_i16_le();
8148 __struct.humidity = buf.get_u16_le();
8149 __struct.id = buf.get_u8();
8150 Ok(__struct)
8151 }
8152 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8153 let mut __tmp = BytesMut::new(bytes);
8154 #[allow(clippy::absurd_extreme_comparisons)]
8155 #[allow(unused_comparisons)]
8156 if __tmp.remaining() < Self::ENCODED_LEN {
8157 panic!(
8158 "buffer is too small (need {} bytes, but got {})",
8159 Self::ENCODED_LEN,
8160 __tmp.remaining(),
8161 )
8162 }
8163 __tmp.put_i16_le(self.temperature);
8164 __tmp.put_u16_le(self.humidity);
8165 __tmp.put_u8(self.id);
8166 if matches!(version, MavlinkVersion::V2) {
8167 let len = __tmp.len();
8168 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8169 } else {
8170 __tmp.len()
8171 }
8172 }
8173}
8174#[doc = "id: 395"]
8175#[doc = "Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE."]
8176#[derive(Debug, Clone, PartialEq)]
8177#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8178#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8179pub struct COMPONENT_INFORMATION_DATA {
8180 #[doc = "Timestamp (time since system boot)."]
8181 pub time_boot_ms: u32,
8182 #[doc = "CRC32 of the general metadata file (general_metadata_uri)."]
8183 pub general_metadata_file_crc: u32,
8184 #[doc = "CRC32 of peripherals metadata file (peripherals_metadata_uri)."]
8185 pub peripherals_metadata_file_crc: u32,
8186 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
8187 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8188 pub general_metadata_uri: [u8; 100],
8189 #[doc = "(Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about \"attached components\" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated."]
8190 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8191 pub peripherals_metadata_uri: [u8; 100],
8192}
8193impl COMPONENT_INFORMATION_DATA {
8194 pub const ENCODED_LEN: usize = 212usize;
8195 pub const DEFAULT: Self = Self {
8196 time_boot_ms: 0_u32,
8197 general_metadata_file_crc: 0_u32,
8198 peripherals_metadata_file_crc: 0_u32,
8199 general_metadata_uri: [0_u8; 100usize],
8200 peripherals_metadata_uri: [0_u8; 100usize],
8201 };
8202 #[cfg(feature = "arbitrary")]
8203 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8204 use arbitrary::{Arbitrary, Unstructured};
8205 let mut buf = [0u8; 1024];
8206 rng.fill_bytes(&mut buf);
8207 let mut unstructured = Unstructured::new(&buf);
8208 Self::arbitrary(&mut unstructured).unwrap_or_default()
8209 }
8210}
8211impl Default for COMPONENT_INFORMATION_DATA {
8212 fn default() -> Self {
8213 Self::DEFAULT.clone()
8214 }
8215}
8216impl MessageData for COMPONENT_INFORMATION_DATA {
8217 type Message = MavMessage;
8218 const ID: u32 = 395u32;
8219 const NAME: &'static str = "COMPONENT_INFORMATION";
8220 const EXTRA_CRC: u8 = 0u8;
8221 const ENCODED_LEN: usize = 212usize;
8222 fn deser(
8223 _version: MavlinkVersion,
8224 __input: &[u8],
8225 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8226 let avail_len = __input.len();
8227 let mut payload_buf = [0; Self::ENCODED_LEN];
8228 let mut buf = if avail_len < Self::ENCODED_LEN {
8229 payload_buf[0..avail_len].copy_from_slice(__input);
8230 Bytes::new(&payload_buf)
8231 } else {
8232 Bytes::new(__input)
8233 };
8234 let mut __struct = Self::default();
8235 __struct.time_boot_ms = buf.get_u32_le();
8236 __struct.general_metadata_file_crc = buf.get_u32_le();
8237 __struct.peripherals_metadata_file_crc = buf.get_u32_le();
8238 for v in &mut __struct.general_metadata_uri {
8239 let val = buf.get_u8();
8240 *v = val;
8241 }
8242 for v in &mut __struct.peripherals_metadata_uri {
8243 let val = buf.get_u8();
8244 *v = val;
8245 }
8246 Ok(__struct)
8247 }
8248 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8249 let mut __tmp = BytesMut::new(bytes);
8250 #[allow(clippy::absurd_extreme_comparisons)]
8251 #[allow(unused_comparisons)]
8252 if __tmp.remaining() < Self::ENCODED_LEN {
8253 panic!(
8254 "buffer is too small (need {} bytes, but got {})",
8255 Self::ENCODED_LEN,
8256 __tmp.remaining(),
8257 )
8258 }
8259 __tmp.put_u32_le(self.time_boot_ms);
8260 __tmp.put_u32_le(self.general_metadata_file_crc);
8261 __tmp.put_u32_le(self.peripherals_metadata_file_crc);
8262 for val in &self.general_metadata_uri {
8263 __tmp.put_u8(*val);
8264 }
8265 for val in &self.peripherals_metadata_uri {
8266 __tmp.put_u8(*val);
8267 }
8268 if matches!(version, MavlinkVersion::V2) {
8269 let len = __tmp.len();
8270 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8271 } else {
8272 __tmp.len()
8273 }
8274 }
8275}
8276#[doc = "id: 136"]
8277#[doc = "Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
8278#[derive(Debug, Clone, PartialEq)]
8279#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8280#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8281pub struct TERRAIN_REPORT_DATA {
8282 #[doc = "Latitude"]
8283 pub lat: i32,
8284 #[doc = "Longitude"]
8285 pub lon: i32,
8286 #[doc = "Terrain height MSL"]
8287 pub terrain_height: f32,
8288 #[doc = "Current vehicle height above lat/lon terrain height"]
8289 pub current_height: f32,
8290 #[doc = "grid spacing (zero if terrain at this location unavailable)"]
8291 pub spacing: u16,
8292 #[doc = "Number of 4x4 terrain blocks waiting to be received or read from disk"]
8293 pub pending: u16,
8294 #[doc = "Number of 4x4 terrain blocks in memory"]
8295 pub loaded: u16,
8296}
8297impl TERRAIN_REPORT_DATA {
8298 pub const ENCODED_LEN: usize = 22usize;
8299 pub const DEFAULT: Self = Self {
8300 lat: 0_i32,
8301 lon: 0_i32,
8302 terrain_height: 0.0_f32,
8303 current_height: 0.0_f32,
8304 spacing: 0_u16,
8305 pending: 0_u16,
8306 loaded: 0_u16,
8307 };
8308 #[cfg(feature = "arbitrary")]
8309 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8310 use arbitrary::{Arbitrary, Unstructured};
8311 let mut buf = [0u8; 1024];
8312 rng.fill_bytes(&mut buf);
8313 let mut unstructured = Unstructured::new(&buf);
8314 Self::arbitrary(&mut unstructured).unwrap_or_default()
8315 }
8316}
8317impl Default for TERRAIN_REPORT_DATA {
8318 fn default() -> Self {
8319 Self::DEFAULT.clone()
8320 }
8321}
8322impl MessageData for TERRAIN_REPORT_DATA {
8323 type Message = MavMessage;
8324 const ID: u32 = 136u32;
8325 const NAME: &'static str = "TERRAIN_REPORT";
8326 const EXTRA_CRC: u8 = 1u8;
8327 const ENCODED_LEN: usize = 22usize;
8328 fn deser(
8329 _version: MavlinkVersion,
8330 __input: &[u8],
8331 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8332 let avail_len = __input.len();
8333 let mut payload_buf = [0; Self::ENCODED_LEN];
8334 let mut buf = if avail_len < Self::ENCODED_LEN {
8335 payload_buf[0..avail_len].copy_from_slice(__input);
8336 Bytes::new(&payload_buf)
8337 } else {
8338 Bytes::new(__input)
8339 };
8340 let mut __struct = Self::default();
8341 __struct.lat = buf.get_i32_le();
8342 __struct.lon = buf.get_i32_le();
8343 __struct.terrain_height = buf.get_f32_le();
8344 __struct.current_height = buf.get_f32_le();
8345 __struct.spacing = buf.get_u16_le();
8346 __struct.pending = buf.get_u16_le();
8347 __struct.loaded = buf.get_u16_le();
8348 Ok(__struct)
8349 }
8350 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8351 let mut __tmp = BytesMut::new(bytes);
8352 #[allow(clippy::absurd_extreme_comparisons)]
8353 #[allow(unused_comparisons)]
8354 if __tmp.remaining() < Self::ENCODED_LEN {
8355 panic!(
8356 "buffer is too small (need {} bytes, but got {})",
8357 Self::ENCODED_LEN,
8358 __tmp.remaining(),
8359 )
8360 }
8361 __tmp.put_i32_le(self.lat);
8362 __tmp.put_i32_le(self.lon);
8363 __tmp.put_f32_le(self.terrain_height);
8364 __tmp.put_f32_le(self.current_height);
8365 __tmp.put_u16_le(self.spacing);
8366 __tmp.put_u16_le(self.pending);
8367 __tmp.put_u16_le(self.loaded);
8368 if matches!(version, MavlinkVersion::V2) {
8369 let len = __tmp.len();
8370 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8371 } else {
8372 __tmp.len()
8373 }
8374 }
8375}
8376#[doc = "id: 137"]
8377#[doc = "Barometer readings for 2nd barometer."]
8378#[derive(Debug, Clone, PartialEq)]
8379#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8380#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8381pub struct SCALED_PRESSURE2_DATA {
8382 #[doc = "Timestamp (time since system boot)."]
8383 pub time_boot_ms: u32,
8384 #[doc = "Absolute pressure"]
8385 pub press_abs: f32,
8386 #[doc = "Differential pressure"]
8387 pub press_diff: f32,
8388 #[doc = "Absolute pressure temperature"]
8389 pub temperature: i16,
8390 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
8391 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8392 pub temperature_press_diff: i16,
8393}
8394impl SCALED_PRESSURE2_DATA {
8395 pub const ENCODED_LEN: usize = 16usize;
8396 pub const DEFAULT: Self = Self {
8397 time_boot_ms: 0_u32,
8398 press_abs: 0.0_f32,
8399 press_diff: 0.0_f32,
8400 temperature: 0_i16,
8401 temperature_press_diff: 0_i16,
8402 };
8403 #[cfg(feature = "arbitrary")]
8404 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8405 use arbitrary::{Arbitrary, Unstructured};
8406 let mut buf = [0u8; 1024];
8407 rng.fill_bytes(&mut buf);
8408 let mut unstructured = Unstructured::new(&buf);
8409 Self::arbitrary(&mut unstructured).unwrap_or_default()
8410 }
8411}
8412impl Default for SCALED_PRESSURE2_DATA {
8413 fn default() -> Self {
8414 Self::DEFAULT.clone()
8415 }
8416}
8417impl MessageData for SCALED_PRESSURE2_DATA {
8418 type Message = MavMessage;
8419 const ID: u32 = 137u32;
8420 const NAME: &'static str = "SCALED_PRESSURE2";
8421 const EXTRA_CRC: u8 = 195u8;
8422 const ENCODED_LEN: usize = 16usize;
8423 fn deser(
8424 _version: MavlinkVersion,
8425 __input: &[u8],
8426 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8427 let avail_len = __input.len();
8428 let mut payload_buf = [0; Self::ENCODED_LEN];
8429 let mut buf = if avail_len < Self::ENCODED_LEN {
8430 payload_buf[0..avail_len].copy_from_slice(__input);
8431 Bytes::new(&payload_buf)
8432 } else {
8433 Bytes::new(__input)
8434 };
8435 let mut __struct = Self::default();
8436 __struct.time_boot_ms = buf.get_u32_le();
8437 __struct.press_abs = buf.get_f32_le();
8438 __struct.press_diff = buf.get_f32_le();
8439 __struct.temperature = buf.get_i16_le();
8440 __struct.temperature_press_diff = buf.get_i16_le();
8441 Ok(__struct)
8442 }
8443 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8444 let mut __tmp = BytesMut::new(bytes);
8445 #[allow(clippy::absurd_extreme_comparisons)]
8446 #[allow(unused_comparisons)]
8447 if __tmp.remaining() < Self::ENCODED_LEN {
8448 panic!(
8449 "buffer is too small (need {} bytes, but got {})",
8450 Self::ENCODED_LEN,
8451 __tmp.remaining(),
8452 )
8453 }
8454 __tmp.put_u32_le(self.time_boot_ms);
8455 __tmp.put_f32_le(self.press_abs);
8456 __tmp.put_f32_le(self.press_diff);
8457 __tmp.put_i16_le(self.temperature);
8458 __tmp.put_i16_le(self.temperature_press_diff);
8459 if matches!(version, MavlinkVersion::V2) {
8460 let len = __tmp.len();
8461 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8462 } else {
8463 __tmp.len()
8464 }
8465 }
8466}
8467#[doc = "id: 259"]
8468#[doc = "Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
8469#[derive(Debug, Clone, PartialEq)]
8470#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8471#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8472pub struct CAMERA_INFORMATION_DATA {
8473 #[doc = "Timestamp (time since system boot)."]
8474 pub time_boot_ms: u32,
8475 #[doc = "0xff). Use 0 if not known."]
8476 pub firmware_version: u32,
8477 #[doc = "Focal length. Use NaN if not known."]
8478 pub focal_length: f32,
8479 #[doc = "Image sensor size horizontal. Use NaN if not known."]
8480 pub sensor_size_h: f32,
8481 #[doc = "Image sensor size vertical. Use NaN if not known."]
8482 pub sensor_size_v: f32,
8483 #[doc = "Bitmap of camera capability flags."]
8484 pub flags: CameraCapFlags,
8485 #[doc = "Horizontal image resolution. Use 0 if not known."]
8486 pub resolution_h: u16,
8487 #[doc = "Vertical image resolution. Use 0 if not known."]
8488 pub resolution_v: u16,
8489 #[doc = "Camera definition version (iteration). Use 0 if not known."]
8490 pub cam_definition_version: u16,
8491 #[doc = "Name of the camera vendor"]
8492 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8493 pub vendor_name: [u8; 32],
8494 #[doc = "Name of the camera model"]
8495 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8496 pub model_name: [u8; 32],
8497 #[doc = "Reserved for a lens ID. Use 0 if not known."]
8498 pub lens_id: u8,
8499 #[doc = "Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known."]
8500 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8501 pub cam_definition_uri: [u8; 140],
8502 #[doc = "Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera."]
8503 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8504 pub gimbal_device_id: u8,
8505 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
8506 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8507 pub camera_device_id: u8,
8508}
8509impl CAMERA_INFORMATION_DATA {
8510 pub const ENCODED_LEN: usize = 237usize;
8511 pub const DEFAULT: Self = Self {
8512 time_boot_ms: 0_u32,
8513 firmware_version: 0_u32,
8514 focal_length: 0.0_f32,
8515 sensor_size_h: 0.0_f32,
8516 sensor_size_v: 0.0_f32,
8517 flags: CameraCapFlags::DEFAULT,
8518 resolution_h: 0_u16,
8519 resolution_v: 0_u16,
8520 cam_definition_version: 0_u16,
8521 vendor_name: [0_u8; 32usize],
8522 model_name: [0_u8; 32usize],
8523 lens_id: 0_u8,
8524 cam_definition_uri: [0_u8; 140usize],
8525 gimbal_device_id: 0_u8,
8526 camera_device_id: 0_u8,
8527 };
8528 #[cfg(feature = "arbitrary")]
8529 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8530 use arbitrary::{Arbitrary, Unstructured};
8531 let mut buf = [0u8; 1024];
8532 rng.fill_bytes(&mut buf);
8533 let mut unstructured = Unstructured::new(&buf);
8534 Self::arbitrary(&mut unstructured).unwrap_or_default()
8535 }
8536}
8537impl Default for CAMERA_INFORMATION_DATA {
8538 fn default() -> Self {
8539 Self::DEFAULT.clone()
8540 }
8541}
8542impl MessageData for CAMERA_INFORMATION_DATA {
8543 type Message = MavMessage;
8544 const ID: u32 = 259u32;
8545 const NAME: &'static str = "CAMERA_INFORMATION";
8546 const EXTRA_CRC: u8 = 92u8;
8547 const ENCODED_LEN: usize = 237usize;
8548 fn deser(
8549 _version: MavlinkVersion,
8550 __input: &[u8],
8551 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8552 let avail_len = __input.len();
8553 let mut payload_buf = [0; Self::ENCODED_LEN];
8554 let mut buf = if avail_len < Self::ENCODED_LEN {
8555 payload_buf[0..avail_len].copy_from_slice(__input);
8556 Bytes::new(&payload_buf)
8557 } else {
8558 Bytes::new(__input)
8559 };
8560 let mut __struct = Self::default();
8561 __struct.time_boot_ms = buf.get_u32_le();
8562 __struct.firmware_version = buf.get_u32_le();
8563 __struct.focal_length = buf.get_f32_le();
8564 __struct.sensor_size_h = buf.get_f32_le();
8565 __struct.sensor_size_v = buf.get_f32_le();
8566 let tmp = buf.get_u32_le();
8567 __struct.flags = CameraCapFlags::from_bits(tmp & CameraCapFlags::all().bits()).ok_or(
8568 ::mavlink_core::error::ParserError::InvalidFlag {
8569 flag_type: "CameraCapFlags",
8570 value: tmp as u32,
8571 },
8572 )?;
8573 __struct.resolution_h = buf.get_u16_le();
8574 __struct.resolution_v = buf.get_u16_le();
8575 __struct.cam_definition_version = buf.get_u16_le();
8576 for v in &mut __struct.vendor_name {
8577 let val = buf.get_u8();
8578 *v = val;
8579 }
8580 for v in &mut __struct.model_name {
8581 let val = buf.get_u8();
8582 *v = val;
8583 }
8584 __struct.lens_id = buf.get_u8();
8585 for v in &mut __struct.cam_definition_uri {
8586 let val = buf.get_u8();
8587 *v = val;
8588 }
8589 __struct.gimbal_device_id = buf.get_u8();
8590 __struct.camera_device_id = buf.get_u8();
8591 Ok(__struct)
8592 }
8593 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8594 let mut __tmp = BytesMut::new(bytes);
8595 #[allow(clippy::absurd_extreme_comparisons)]
8596 #[allow(unused_comparisons)]
8597 if __tmp.remaining() < Self::ENCODED_LEN {
8598 panic!(
8599 "buffer is too small (need {} bytes, but got {})",
8600 Self::ENCODED_LEN,
8601 __tmp.remaining(),
8602 )
8603 }
8604 __tmp.put_u32_le(self.time_boot_ms);
8605 __tmp.put_u32_le(self.firmware_version);
8606 __tmp.put_f32_le(self.focal_length);
8607 __tmp.put_f32_le(self.sensor_size_h);
8608 __tmp.put_f32_le(self.sensor_size_v);
8609 __tmp.put_u32_le(self.flags.bits());
8610 __tmp.put_u16_le(self.resolution_h);
8611 __tmp.put_u16_le(self.resolution_v);
8612 __tmp.put_u16_le(self.cam_definition_version);
8613 for val in &self.vendor_name {
8614 __tmp.put_u8(*val);
8615 }
8616 for val in &self.model_name {
8617 __tmp.put_u8(*val);
8618 }
8619 __tmp.put_u8(self.lens_id);
8620 for val in &self.cam_definition_uri {
8621 __tmp.put_u8(*val);
8622 }
8623 __tmp.put_u8(self.gimbal_device_id);
8624 __tmp.put_u8(self.camera_device_id);
8625 if matches!(version, MavlinkVersion::V2) {
8626 let len = __tmp.len();
8627 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8628 } else {
8629 __tmp.len()
8630 }
8631 }
8632}
8633#[doc = "id: 235"]
8634#[doc = "Message appropriate for high latency connections like Iridium (version 2)."]
8635#[derive(Debug, Clone, PartialEq)]
8636#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8637#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8638pub struct HIGH_LATENCY2_DATA {
8639 #[doc = "Timestamp (milliseconds since boot or Unix epoch)"]
8640 pub timestamp: u32,
8641 #[doc = "Latitude"]
8642 pub latitude: i32,
8643 #[doc = "Longitude"]
8644 pub longitude: i32,
8645 #[doc = "A bitfield for use for autopilot-specific flags (2 byte version)."]
8646 pub custom_mode: u16,
8647 #[doc = "Altitude above mean sea level"]
8648 pub altitude: i16,
8649 #[doc = "Altitude setpoint"]
8650 pub target_altitude: i16,
8651 #[doc = "Distance to target waypoint or position"]
8652 pub target_distance: u16,
8653 #[doc = "Current waypoint number"]
8654 pub wp_num: u16,
8655 #[doc = "Bitmap of failure flags."]
8656 pub failure_flags: HlFailureFlag,
8657 #[doc = "Type of the MAV (quadrotor, helicopter, etc.)"]
8658 pub mavtype: MavType,
8659 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
8660 pub autopilot: MavAutopilot,
8661 #[doc = "Heading"]
8662 pub heading: u8,
8663 #[doc = "Heading setpoint"]
8664 pub target_heading: u8,
8665 #[doc = "Throttle"]
8666 pub throttle: u8,
8667 #[doc = "Airspeed"]
8668 pub airspeed: u8,
8669 #[doc = "Airspeed setpoint"]
8670 pub airspeed_sp: u8,
8671 #[doc = "Groundspeed"]
8672 pub groundspeed: u8,
8673 #[doc = "Windspeed"]
8674 pub windspeed: u8,
8675 #[doc = "Wind heading"]
8676 pub wind_heading: u8,
8677 #[doc = "Maximum error horizontal position since last message"]
8678 pub eph: u8,
8679 #[doc = "Maximum error vertical position since last message"]
8680 pub epv: u8,
8681 #[doc = "Air temperature"]
8682 pub temperature_air: i8,
8683 #[doc = "Maximum climb rate magnitude since last message"]
8684 pub climb_rate: i8,
8685 #[doc = "Battery level (-1 if field not provided)."]
8686 pub battery: i8,
8687 #[doc = "Field for custom payload."]
8688 pub custom0: i8,
8689 #[doc = "Field for custom payload."]
8690 pub custom1: i8,
8691 #[doc = "Field for custom payload."]
8692 pub custom2: i8,
8693}
8694impl HIGH_LATENCY2_DATA {
8695 pub const ENCODED_LEN: usize = 42usize;
8696 pub const DEFAULT: Self = Self {
8697 timestamp: 0_u32,
8698 latitude: 0_i32,
8699 longitude: 0_i32,
8700 custom_mode: 0_u16,
8701 altitude: 0_i16,
8702 target_altitude: 0_i16,
8703 target_distance: 0_u16,
8704 wp_num: 0_u16,
8705 failure_flags: HlFailureFlag::DEFAULT,
8706 mavtype: MavType::DEFAULT,
8707 autopilot: MavAutopilot::DEFAULT,
8708 heading: 0_u8,
8709 target_heading: 0_u8,
8710 throttle: 0_u8,
8711 airspeed: 0_u8,
8712 airspeed_sp: 0_u8,
8713 groundspeed: 0_u8,
8714 windspeed: 0_u8,
8715 wind_heading: 0_u8,
8716 eph: 0_u8,
8717 epv: 0_u8,
8718 temperature_air: 0_i8,
8719 climb_rate: 0_i8,
8720 battery: 0_i8,
8721 custom0: 0_i8,
8722 custom1: 0_i8,
8723 custom2: 0_i8,
8724 };
8725 #[cfg(feature = "arbitrary")]
8726 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8727 use arbitrary::{Arbitrary, Unstructured};
8728 let mut buf = [0u8; 1024];
8729 rng.fill_bytes(&mut buf);
8730 let mut unstructured = Unstructured::new(&buf);
8731 Self::arbitrary(&mut unstructured).unwrap_or_default()
8732 }
8733}
8734impl Default for HIGH_LATENCY2_DATA {
8735 fn default() -> Self {
8736 Self::DEFAULT.clone()
8737 }
8738}
8739impl MessageData for HIGH_LATENCY2_DATA {
8740 type Message = MavMessage;
8741 const ID: u32 = 235u32;
8742 const NAME: &'static str = "HIGH_LATENCY2";
8743 const EXTRA_CRC: u8 = 179u8;
8744 const ENCODED_LEN: usize = 42usize;
8745 fn deser(
8746 _version: MavlinkVersion,
8747 __input: &[u8],
8748 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8749 let avail_len = __input.len();
8750 let mut payload_buf = [0; Self::ENCODED_LEN];
8751 let mut buf = if avail_len < Self::ENCODED_LEN {
8752 payload_buf[0..avail_len].copy_from_slice(__input);
8753 Bytes::new(&payload_buf)
8754 } else {
8755 Bytes::new(__input)
8756 };
8757 let mut __struct = Self::default();
8758 __struct.timestamp = buf.get_u32_le();
8759 __struct.latitude = buf.get_i32_le();
8760 __struct.longitude = buf.get_i32_le();
8761 __struct.custom_mode = buf.get_u16_le();
8762 __struct.altitude = buf.get_i16_le();
8763 __struct.target_altitude = buf.get_i16_le();
8764 __struct.target_distance = buf.get_u16_le();
8765 __struct.wp_num = buf.get_u16_le();
8766 let tmp = buf.get_u16_le();
8767 __struct.failure_flags = HlFailureFlag::from_bits(tmp & HlFailureFlag::all().bits())
8768 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
8769 flag_type: "HlFailureFlag",
8770 value: tmp as u32,
8771 })?;
8772 let tmp = buf.get_u8();
8773 __struct.mavtype =
8774 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8775 enum_type: "MavType",
8776 value: tmp as u32,
8777 })?;
8778 let tmp = buf.get_u8();
8779 __struct.autopilot =
8780 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8781 enum_type: "MavAutopilot",
8782 value: tmp as u32,
8783 })?;
8784 __struct.heading = buf.get_u8();
8785 __struct.target_heading = buf.get_u8();
8786 __struct.throttle = buf.get_u8();
8787 __struct.airspeed = buf.get_u8();
8788 __struct.airspeed_sp = buf.get_u8();
8789 __struct.groundspeed = buf.get_u8();
8790 __struct.windspeed = buf.get_u8();
8791 __struct.wind_heading = buf.get_u8();
8792 __struct.eph = buf.get_u8();
8793 __struct.epv = buf.get_u8();
8794 __struct.temperature_air = buf.get_i8();
8795 __struct.climb_rate = buf.get_i8();
8796 __struct.battery = buf.get_i8();
8797 __struct.custom0 = buf.get_i8();
8798 __struct.custom1 = buf.get_i8();
8799 __struct.custom2 = buf.get_i8();
8800 Ok(__struct)
8801 }
8802 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8803 let mut __tmp = BytesMut::new(bytes);
8804 #[allow(clippy::absurd_extreme_comparisons)]
8805 #[allow(unused_comparisons)]
8806 if __tmp.remaining() < Self::ENCODED_LEN {
8807 panic!(
8808 "buffer is too small (need {} bytes, but got {})",
8809 Self::ENCODED_LEN,
8810 __tmp.remaining(),
8811 )
8812 }
8813 __tmp.put_u32_le(self.timestamp);
8814 __tmp.put_i32_le(self.latitude);
8815 __tmp.put_i32_le(self.longitude);
8816 __tmp.put_u16_le(self.custom_mode);
8817 __tmp.put_i16_le(self.altitude);
8818 __tmp.put_i16_le(self.target_altitude);
8819 __tmp.put_u16_le(self.target_distance);
8820 __tmp.put_u16_le(self.wp_num);
8821 __tmp.put_u16_le(self.failure_flags.bits());
8822 __tmp.put_u8(self.mavtype as u8);
8823 __tmp.put_u8(self.autopilot as u8);
8824 __tmp.put_u8(self.heading);
8825 __tmp.put_u8(self.target_heading);
8826 __tmp.put_u8(self.throttle);
8827 __tmp.put_u8(self.airspeed);
8828 __tmp.put_u8(self.airspeed_sp);
8829 __tmp.put_u8(self.groundspeed);
8830 __tmp.put_u8(self.windspeed);
8831 __tmp.put_u8(self.wind_heading);
8832 __tmp.put_u8(self.eph);
8833 __tmp.put_u8(self.epv);
8834 __tmp.put_i8(self.temperature_air);
8835 __tmp.put_i8(self.climb_rate);
8836 __tmp.put_i8(self.battery);
8837 __tmp.put_i8(self.custom0);
8838 __tmp.put_i8(self.custom1);
8839 __tmp.put_i8(self.custom2);
8840 if matches!(version, MavlinkVersion::V2) {
8841 let len = __tmp.len();
8842 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8843 } else {
8844 __tmp.len()
8845 }
8846 }
8847}
8848#[doc = "id: 246"]
8849#[doc = "The location and information of an ADSB vehicle."]
8850#[derive(Debug, Clone, PartialEq)]
8851#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8852#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8853pub struct ADSB_VEHICLE_DATA {
8854 #[doc = "ICAO address"]
8855 pub ICAO_address: u32,
8856 #[doc = "Latitude"]
8857 pub lat: i32,
8858 #[doc = "Longitude"]
8859 pub lon: i32,
8860 #[doc = "Altitude(ASL)"]
8861 pub altitude: i32,
8862 #[doc = "Course over ground"]
8863 pub heading: u16,
8864 #[doc = "The horizontal velocity"]
8865 pub hor_velocity: u16,
8866 #[doc = "The vertical velocity. Positive is up"]
8867 pub ver_velocity: i16,
8868 #[doc = "Bitmap to indicate various statuses including valid data fields"]
8869 pub flags: AdsbFlags,
8870 #[doc = "Squawk code. Note that the code is in decimal: e.g. 7700 (general emergency) is encoded as binary 0b0001_1110_0001_0100, not(!) as 0b0000_111_111_000_000"]
8871 pub squawk: u16,
8872 #[doc = "ADSB altitude type."]
8873 pub altitude_type: AdsbAltitudeType,
8874 #[doc = "The callsign, 8+null"]
8875 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8876 pub callsign: [u8; 9],
8877 #[doc = "ADSB emitter type."]
8878 pub emitter_type: AdsbEmitterType,
8879 #[doc = "Time since last communication in seconds"]
8880 pub tslc: u8,
8881}
8882impl ADSB_VEHICLE_DATA {
8883 pub const ENCODED_LEN: usize = 38usize;
8884 pub const DEFAULT: Self = Self {
8885 ICAO_address: 0_u32,
8886 lat: 0_i32,
8887 lon: 0_i32,
8888 altitude: 0_i32,
8889 heading: 0_u16,
8890 hor_velocity: 0_u16,
8891 ver_velocity: 0_i16,
8892 flags: AdsbFlags::DEFAULT,
8893 squawk: 0_u16,
8894 altitude_type: AdsbAltitudeType::DEFAULT,
8895 callsign: [0_u8; 9usize],
8896 emitter_type: AdsbEmitterType::DEFAULT,
8897 tslc: 0_u8,
8898 };
8899 #[cfg(feature = "arbitrary")]
8900 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8901 use arbitrary::{Arbitrary, Unstructured};
8902 let mut buf = [0u8; 1024];
8903 rng.fill_bytes(&mut buf);
8904 let mut unstructured = Unstructured::new(&buf);
8905 Self::arbitrary(&mut unstructured).unwrap_or_default()
8906 }
8907}
8908impl Default for ADSB_VEHICLE_DATA {
8909 fn default() -> Self {
8910 Self::DEFAULT.clone()
8911 }
8912}
8913impl MessageData for ADSB_VEHICLE_DATA {
8914 type Message = MavMessage;
8915 const ID: u32 = 246u32;
8916 const NAME: &'static str = "ADSB_VEHICLE";
8917 const EXTRA_CRC: u8 = 184u8;
8918 const ENCODED_LEN: usize = 38usize;
8919 fn deser(
8920 _version: MavlinkVersion,
8921 __input: &[u8],
8922 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8923 let avail_len = __input.len();
8924 let mut payload_buf = [0; Self::ENCODED_LEN];
8925 let mut buf = if avail_len < Self::ENCODED_LEN {
8926 payload_buf[0..avail_len].copy_from_slice(__input);
8927 Bytes::new(&payload_buf)
8928 } else {
8929 Bytes::new(__input)
8930 };
8931 let mut __struct = Self::default();
8932 __struct.ICAO_address = buf.get_u32_le();
8933 __struct.lat = buf.get_i32_le();
8934 __struct.lon = buf.get_i32_le();
8935 __struct.altitude = buf.get_i32_le();
8936 __struct.heading = buf.get_u16_le();
8937 __struct.hor_velocity = buf.get_u16_le();
8938 __struct.ver_velocity = buf.get_i16_le();
8939 let tmp = buf.get_u16_le();
8940 __struct.flags = AdsbFlags::from_bits(tmp & AdsbFlags::all().bits()).ok_or(
8941 ::mavlink_core::error::ParserError::InvalidFlag {
8942 flag_type: "AdsbFlags",
8943 value: tmp as u32,
8944 },
8945 )?;
8946 __struct.squawk = buf.get_u16_le();
8947 let tmp = buf.get_u8();
8948 __struct.altitude_type =
8949 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8950 enum_type: "AdsbAltitudeType",
8951 value: tmp as u32,
8952 })?;
8953 for v in &mut __struct.callsign {
8954 let val = buf.get_u8();
8955 *v = val;
8956 }
8957 let tmp = buf.get_u8();
8958 __struct.emitter_type =
8959 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8960 enum_type: "AdsbEmitterType",
8961 value: tmp as u32,
8962 })?;
8963 __struct.tslc = buf.get_u8();
8964 Ok(__struct)
8965 }
8966 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8967 let mut __tmp = BytesMut::new(bytes);
8968 #[allow(clippy::absurd_extreme_comparisons)]
8969 #[allow(unused_comparisons)]
8970 if __tmp.remaining() < Self::ENCODED_LEN {
8971 panic!(
8972 "buffer is too small (need {} bytes, but got {})",
8973 Self::ENCODED_LEN,
8974 __tmp.remaining(),
8975 )
8976 }
8977 __tmp.put_u32_le(self.ICAO_address);
8978 __tmp.put_i32_le(self.lat);
8979 __tmp.put_i32_le(self.lon);
8980 __tmp.put_i32_le(self.altitude);
8981 __tmp.put_u16_le(self.heading);
8982 __tmp.put_u16_le(self.hor_velocity);
8983 __tmp.put_i16_le(self.ver_velocity);
8984 __tmp.put_u16_le(self.flags.bits());
8985 __tmp.put_u16_le(self.squawk);
8986 __tmp.put_u8(self.altitude_type as u8);
8987 for val in &self.callsign {
8988 __tmp.put_u8(*val);
8989 }
8990 __tmp.put_u8(self.emitter_type as u8);
8991 __tmp.put_u8(self.tslc);
8992 if matches!(version, MavlinkVersion::V2) {
8993 let len = __tmp.len();
8994 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8995 } else {
8996 __tmp.len()
8997 }
8998 }
8999}
9000#[doc = "id: 74"]
9001#[doc = "Metrics typically displayed on a HUD for fixed wing aircraft."]
9002#[derive(Debug, Clone, PartialEq)]
9003#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9004#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9005pub struct VFR_HUD_DATA {
9006 #[doc = "Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed."]
9007 pub airspeed: f32,
9008 #[doc = "Current ground speed."]
9009 pub groundspeed: f32,
9010 #[doc = "Current altitude (MSL)."]
9011 pub alt: f32,
9012 #[doc = "Current climb rate."]
9013 pub climb: f32,
9014 #[doc = "Current heading in compass units (0-360, 0=north)."]
9015 pub heading: i16,
9016 #[doc = "Current throttle setting (0 to 100)."]
9017 pub throttle: u16,
9018}
9019impl VFR_HUD_DATA {
9020 pub const ENCODED_LEN: usize = 20usize;
9021 pub const DEFAULT: Self = Self {
9022 airspeed: 0.0_f32,
9023 groundspeed: 0.0_f32,
9024 alt: 0.0_f32,
9025 climb: 0.0_f32,
9026 heading: 0_i16,
9027 throttle: 0_u16,
9028 };
9029 #[cfg(feature = "arbitrary")]
9030 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9031 use arbitrary::{Arbitrary, Unstructured};
9032 let mut buf = [0u8; 1024];
9033 rng.fill_bytes(&mut buf);
9034 let mut unstructured = Unstructured::new(&buf);
9035 Self::arbitrary(&mut unstructured).unwrap_or_default()
9036 }
9037}
9038impl Default for VFR_HUD_DATA {
9039 fn default() -> Self {
9040 Self::DEFAULT.clone()
9041 }
9042}
9043impl MessageData for VFR_HUD_DATA {
9044 type Message = MavMessage;
9045 const ID: u32 = 74u32;
9046 const NAME: &'static str = "VFR_HUD";
9047 const EXTRA_CRC: u8 = 20u8;
9048 const ENCODED_LEN: usize = 20usize;
9049 fn deser(
9050 _version: MavlinkVersion,
9051 __input: &[u8],
9052 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9053 let avail_len = __input.len();
9054 let mut payload_buf = [0; Self::ENCODED_LEN];
9055 let mut buf = if avail_len < Self::ENCODED_LEN {
9056 payload_buf[0..avail_len].copy_from_slice(__input);
9057 Bytes::new(&payload_buf)
9058 } else {
9059 Bytes::new(__input)
9060 };
9061 let mut __struct = Self::default();
9062 __struct.airspeed = buf.get_f32_le();
9063 __struct.groundspeed = buf.get_f32_le();
9064 __struct.alt = buf.get_f32_le();
9065 __struct.climb = buf.get_f32_le();
9066 __struct.heading = buf.get_i16_le();
9067 __struct.throttle = buf.get_u16_le();
9068 Ok(__struct)
9069 }
9070 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9071 let mut __tmp = BytesMut::new(bytes);
9072 #[allow(clippy::absurd_extreme_comparisons)]
9073 #[allow(unused_comparisons)]
9074 if __tmp.remaining() < Self::ENCODED_LEN {
9075 panic!(
9076 "buffer is too small (need {} bytes, but got {})",
9077 Self::ENCODED_LEN,
9078 __tmp.remaining(),
9079 )
9080 }
9081 __tmp.put_f32_le(self.airspeed);
9082 __tmp.put_f32_le(self.groundspeed);
9083 __tmp.put_f32_le(self.alt);
9084 __tmp.put_f32_le(self.climb);
9085 __tmp.put_i16_le(self.heading);
9086 __tmp.put_u16_le(self.throttle);
9087 if matches!(version, MavlinkVersion::V2) {
9088 let len = __tmp.len();
9089 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9090 } else {
9091 __tmp.len()
9092 }
9093 }
9094}
9095#[doc = "id: 141"]
9096#[doc = "The current system altitude."]
9097#[derive(Debug, Clone, PartialEq)]
9098#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9099#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9100pub struct ALTITUDE_DATA {
9101 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
9102 pub time_usec: u64,
9103 #[doc = "This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights."]
9104 pub altitude_monotonic: f32,
9105 #[doc = "This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude."]
9106 pub altitude_amsl: f32,
9107 #[doc = "This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive."]
9108 pub altitude_local: f32,
9109 #[doc = "This is the altitude above the home position. It resets on each change of the current home position."]
9110 pub altitude_relative: f32,
9111 #[doc = "This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown."]
9112 pub altitude_terrain: f32,
9113 #[doc = "This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available."]
9114 pub bottom_clearance: f32,
9115}
9116impl ALTITUDE_DATA {
9117 pub const ENCODED_LEN: usize = 32usize;
9118 pub const DEFAULT: Self = Self {
9119 time_usec: 0_u64,
9120 altitude_monotonic: 0.0_f32,
9121 altitude_amsl: 0.0_f32,
9122 altitude_local: 0.0_f32,
9123 altitude_relative: 0.0_f32,
9124 altitude_terrain: 0.0_f32,
9125 bottom_clearance: 0.0_f32,
9126 };
9127 #[cfg(feature = "arbitrary")]
9128 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9129 use arbitrary::{Arbitrary, Unstructured};
9130 let mut buf = [0u8; 1024];
9131 rng.fill_bytes(&mut buf);
9132 let mut unstructured = Unstructured::new(&buf);
9133 Self::arbitrary(&mut unstructured).unwrap_or_default()
9134 }
9135}
9136impl Default for ALTITUDE_DATA {
9137 fn default() -> Self {
9138 Self::DEFAULT.clone()
9139 }
9140}
9141impl MessageData for ALTITUDE_DATA {
9142 type Message = MavMessage;
9143 const ID: u32 = 141u32;
9144 const NAME: &'static str = "ALTITUDE";
9145 const EXTRA_CRC: u8 = 47u8;
9146 const ENCODED_LEN: usize = 32usize;
9147 fn deser(
9148 _version: MavlinkVersion,
9149 __input: &[u8],
9150 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9151 let avail_len = __input.len();
9152 let mut payload_buf = [0; Self::ENCODED_LEN];
9153 let mut buf = if avail_len < Self::ENCODED_LEN {
9154 payload_buf[0..avail_len].copy_from_slice(__input);
9155 Bytes::new(&payload_buf)
9156 } else {
9157 Bytes::new(__input)
9158 };
9159 let mut __struct = Self::default();
9160 __struct.time_usec = buf.get_u64_le();
9161 __struct.altitude_monotonic = buf.get_f32_le();
9162 __struct.altitude_amsl = buf.get_f32_le();
9163 __struct.altitude_local = buf.get_f32_le();
9164 __struct.altitude_relative = buf.get_f32_le();
9165 __struct.altitude_terrain = buf.get_f32_le();
9166 __struct.bottom_clearance = buf.get_f32_le();
9167 Ok(__struct)
9168 }
9169 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9170 let mut __tmp = BytesMut::new(bytes);
9171 #[allow(clippy::absurd_extreme_comparisons)]
9172 #[allow(unused_comparisons)]
9173 if __tmp.remaining() < Self::ENCODED_LEN {
9174 panic!(
9175 "buffer is too small (need {} bytes, but got {})",
9176 Self::ENCODED_LEN,
9177 __tmp.remaining(),
9178 )
9179 }
9180 __tmp.put_u64_le(self.time_usec);
9181 __tmp.put_f32_le(self.altitude_monotonic);
9182 __tmp.put_f32_le(self.altitude_amsl);
9183 __tmp.put_f32_le(self.altitude_local);
9184 __tmp.put_f32_le(self.altitude_relative);
9185 __tmp.put_f32_le(self.altitude_terrain);
9186 __tmp.put_f32_le(self.bottom_clearance);
9187 if matches!(version, MavlinkVersion::V2) {
9188 let len = __tmp.len();
9189 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9190 } else {
9191 __tmp.len()
9192 }
9193 }
9194}
9195#[doc = "id: 40"]
9196#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. <https://mavlink.io/en/services/mission.html>."]
9197#[derive(Debug, Clone, PartialEq)]
9198#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9199#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9200pub struct MISSION_REQUEST_DATA {
9201 #[doc = "Sequence"]
9202 pub seq: u16,
9203 #[doc = "System ID"]
9204 pub target_system: u8,
9205 #[doc = "Component ID"]
9206 pub target_component: u8,
9207 #[doc = "Mission type."]
9208 #[cfg_attr(feature = "serde", serde(default))]
9209 pub mission_type: MavMissionType,
9210}
9211impl MISSION_REQUEST_DATA {
9212 pub const ENCODED_LEN: usize = 5usize;
9213 pub const DEFAULT: Self = Self {
9214 seq: 0_u16,
9215 target_system: 0_u8,
9216 target_component: 0_u8,
9217 mission_type: MavMissionType::DEFAULT,
9218 };
9219 #[cfg(feature = "arbitrary")]
9220 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9221 use arbitrary::{Arbitrary, Unstructured};
9222 let mut buf = [0u8; 1024];
9223 rng.fill_bytes(&mut buf);
9224 let mut unstructured = Unstructured::new(&buf);
9225 Self::arbitrary(&mut unstructured).unwrap_or_default()
9226 }
9227}
9228impl Default for MISSION_REQUEST_DATA {
9229 fn default() -> Self {
9230 Self::DEFAULT.clone()
9231 }
9232}
9233impl MessageData for MISSION_REQUEST_DATA {
9234 type Message = MavMessage;
9235 const ID: u32 = 40u32;
9236 const NAME: &'static str = "MISSION_REQUEST";
9237 const EXTRA_CRC: u8 = 230u8;
9238 const ENCODED_LEN: usize = 5usize;
9239 fn deser(
9240 _version: MavlinkVersion,
9241 __input: &[u8],
9242 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9243 let avail_len = __input.len();
9244 let mut payload_buf = [0; Self::ENCODED_LEN];
9245 let mut buf = if avail_len < Self::ENCODED_LEN {
9246 payload_buf[0..avail_len].copy_from_slice(__input);
9247 Bytes::new(&payload_buf)
9248 } else {
9249 Bytes::new(__input)
9250 };
9251 let mut __struct = Self::default();
9252 __struct.seq = buf.get_u16_le();
9253 __struct.target_system = buf.get_u8();
9254 __struct.target_component = buf.get_u8();
9255 let tmp = buf.get_u8();
9256 __struct.mission_type =
9257 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9258 enum_type: "MavMissionType",
9259 value: tmp as u32,
9260 })?;
9261 Ok(__struct)
9262 }
9263 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9264 let mut __tmp = BytesMut::new(bytes);
9265 #[allow(clippy::absurd_extreme_comparisons)]
9266 #[allow(unused_comparisons)]
9267 if __tmp.remaining() < Self::ENCODED_LEN {
9268 panic!(
9269 "buffer is too small (need {} bytes, but got {})",
9270 Self::ENCODED_LEN,
9271 __tmp.remaining(),
9272 )
9273 }
9274 __tmp.put_u16_le(self.seq);
9275 __tmp.put_u8(self.target_system);
9276 __tmp.put_u8(self.target_component);
9277 __tmp.put_u8(self.mission_type as u8);
9278 if matches!(version, MavlinkVersion::V2) {
9279 let len = __tmp.len();
9280 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9281 } else {
9282 __tmp.len()
9283 }
9284 }
9285}
9286#[doc = "id: 387"]
9287#[doc = "A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)."]
9288#[derive(Debug, Clone, PartialEq)]
9289#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9290#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9291pub struct CANFD_FRAME_DATA {
9292 #[doc = "Frame ID"]
9293 pub id: u32,
9294 #[doc = "System ID."]
9295 pub target_system: u8,
9296 #[doc = "Component ID."]
9297 pub target_component: u8,
9298 #[doc = "bus number"]
9299 pub bus: u8,
9300 #[doc = "Frame length"]
9301 pub len: u8,
9302 #[doc = "Frame data"]
9303 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9304 pub data: [u8; 64],
9305}
9306impl CANFD_FRAME_DATA {
9307 pub const ENCODED_LEN: usize = 72usize;
9308 pub const DEFAULT: Self = Self {
9309 id: 0_u32,
9310 target_system: 0_u8,
9311 target_component: 0_u8,
9312 bus: 0_u8,
9313 len: 0_u8,
9314 data: [0_u8; 64usize],
9315 };
9316 #[cfg(feature = "arbitrary")]
9317 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9318 use arbitrary::{Arbitrary, Unstructured};
9319 let mut buf = [0u8; 1024];
9320 rng.fill_bytes(&mut buf);
9321 let mut unstructured = Unstructured::new(&buf);
9322 Self::arbitrary(&mut unstructured).unwrap_or_default()
9323 }
9324}
9325impl Default for CANFD_FRAME_DATA {
9326 fn default() -> Self {
9327 Self::DEFAULT.clone()
9328 }
9329}
9330impl MessageData for CANFD_FRAME_DATA {
9331 type Message = MavMessage;
9332 const ID: u32 = 387u32;
9333 const NAME: &'static str = "CANFD_FRAME";
9334 const EXTRA_CRC: u8 = 4u8;
9335 const ENCODED_LEN: usize = 72usize;
9336 fn deser(
9337 _version: MavlinkVersion,
9338 __input: &[u8],
9339 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9340 let avail_len = __input.len();
9341 let mut payload_buf = [0; Self::ENCODED_LEN];
9342 let mut buf = if avail_len < Self::ENCODED_LEN {
9343 payload_buf[0..avail_len].copy_from_slice(__input);
9344 Bytes::new(&payload_buf)
9345 } else {
9346 Bytes::new(__input)
9347 };
9348 let mut __struct = Self::default();
9349 __struct.id = buf.get_u32_le();
9350 __struct.target_system = buf.get_u8();
9351 __struct.target_component = buf.get_u8();
9352 __struct.bus = buf.get_u8();
9353 __struct.len = buf.get_u8();
9354 for v in &mut __struct.data {
9355 let val = buf.get_u8();
9356 *v = val;
9357 }
9358 Ok(__struct)
9359 }
9360 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9361 let mut __tmp = BytesMut::new(bytes);
9362 #[allow(clippy::absurd_extreme_comparisons)]
9363 #[allow(unused_comparisons)]
9364 if __tmp.remaining() < Self::ENCODED_LEN {
9365 panic!(
9366 "buffer is too small (need {} bytes, but got {})",
9367 Self::ENCODED_LEN,
9368 __tmp.remaining(),
9369 )
9370 }
9371 __tmp.put_u32_le(self.id);
9372 __tmp.put_u8(self.target_system);
9373 __tmp.put_u8(self.target_component);
9374 __tmp.put_u8(self.bus);
9375 __tmp.put_u8(self.len);
9376 for val in &self.data {
9377 __tmp.put_u8(*val);
9378 }
9379 if matches!(version, MavlinkVersion::V2) {
9380 let len = __tmp.len();
9381 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9382 } else {
9383 __tmp.len()
9384 }
9385 }
9386}
9387#[doc = "id: 62"]
9388#[doc = "The state of the navigation and position controller."]
9389#[derive(Debug, Clone, PartialEq)]
9390#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9391#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9392pub struct NAV_CONTROLLER_OUTPUT_DATA {
9393 #[doc = "Current desired roll"]
9394 pub nav_roll: f32,
9395 #[doc = "Current desired pitch"]
9396 pub nav_pitch: f32,
9397 #[doc = "Current altitude error"]
9398 pub alt_error: f32,
9399 #[doc = "Current airspeed error"]
9400 pub aspd_error: f32,
9401 #[doc = "Current crosstrack error on x-y plane"]
9402 pub xtrack_error: f32,
9403 #[doc = "Current desired heading"]
9404 pub nav_bearing: i16,
9405 #[doc = "Bearing to current waypoint/target"]
9406 pub target_bearing: i16,
9407 #[doc = "Distance to active waypoint"]
9408 pub wp_dist: u16,
9409}
9410impl NAV_CONTROLLER_OUTPUT_DATA {
9411 pub const ENCODED_LEN: usize = 26usize;
9412 pub const DEFAULT: Self = Self {
9413 nav_roll: 0.0_f32,
9414 nav_pitch: 0.0_f32,
9415 alt_error: 0.0_f32,
9416 aspd_error: 0.0_f32,
9417 xtrack_error: 0.0_f32,
9418 nav_bearing: 0_i16,
9419 target_bearing: 0_i16,
9420 wp_dist: 0_u16,
9421 };
9422 #[cfg(feature = "arbitrary")]
9423 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9424 use arbitrary::{Arbitrary, Unstructured};
9425 let mut buf = [0u8; 1024];
9426 rng.fill_bytes(&mut buf);
9427 let mut unstructured = Unstructured::new(&buf);
9428 Self::arbitrary(&mut unstructured).unwrap_or_default()
9429 }
9430}
9431impl Default for NAV_CONTROLLER_OUTPUT_DATA {
9432 fn default() -> Self {
9433 Self::DEFAULT.clone()
9434 }
9435}
9436impl MessageData for NAV_CONTROLLER_OUTPUT_DATA {
9437 type Message = MavMessage;
9438 const ID: u32 = 62u32;
9439 const NAME: &'static str = "NAV_CONTROLLER_OUTPUT";
9440 const EXTRA_CRC: u8 = 183u8;
9441 const ENCODED_LEN: usize = 26usize;
9442 fn deser(
9443 _version: MavlinkVersion,
9444 __input: &[u8],
9445 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9446 let avail_len = __input.len();
9447 let mut payload_buf = [0; Self::ENCODED_LEN];
9448 let mut buf = if avail_len < Self::ENCODED_LEN {
9449 payload_buf[0..avail_len].copy_from_slice(__input);
9450 Bytes::new(&payload_buf)
9451 } else {
9452 Bytes::new(__input)
9453 };
9454 let mut __struct = Self::default();
9455 __struct.nav_roll = buf.get_f32_le();
9456 __struct.nav_pitch = buf.get_f32_le();
9457 __struct.alt_error = buf.get_f32_le();
9458 __struct.aspd_error = buf.get_f32_le();
9459 __struct.xtrack_error = buf.get_f32_le();
9460 __struct.nav_bearing = buf.get_i16_le();
9461 __struct.target_bearing = buf.get_i16_le();
9462 __struct.wp_dist = buf.get_u16_le();
9463 Ok(__struct)
9464 }
9465 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9466 let mut __tmp = BytesMut::new(bytes);
9467 #[allow(clippy::absurd_extreme_comparisons)]
9468 #[allow(unused_comparisons)]
9469 if __tmp.remaining() < Self::ENCODED_LEN {
9470 panic!(
9471 "buffer is too small (need {} bytes, but got {})",
9472 Self::ENCODED_LEN,
9473 __tmp.remaining(),
9474 )
9475 }
9476 __tmp.put_f32_le(self.nav_roll);
9477 __tmp.put_f32_le(self.nav_pitch);
9478 __tmp.put_f32_le(self.alt_error);
9479 __tmp.put_f32_le(self.aspd_error);
9480 __tmp.put_f32_le(self.xtrack_error);
9481 __tmp.put_i16_le(self.nav_bearing);
9482 __tmp.put_i16_le(self.target_bearing);
9483 __tmp.put_u16_le(self.wp_dist);
9484 if matches!(version, MavlinkVersion::V2) {
9485 let len = __tmp.len();
9486 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9487 } else {
9488 __tmp.len()
9489 }
9490 }
9491}
9492#[doc = "id: 91"]
9493#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_ACTUATOR_CONTROLS."]
9494#[derive(Debug, Clone, PartialEq)]
9495#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9496#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9497pub struct HIL_CONTROLS_DATA {
9498 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
9499 pub time_usec: u64,
9500 #[doc = "Control output -1 .. 1"]
9501 pub roll_ailerons: f32,
9502 #[doc = "Control output -1 .. 1"]
9503 pub pitch_elevator: f32,
9504 #[doc = "Control output -1 .. 1"]
9505 pub yaw_rudder: f32,
9506 #[doc = "Throttle 0 .. 1"]
9507 pub throttle: f32,
9508 #[doc = "Aux 1, -1 .. 1"]
9509 pub aux1: f32,
9510 #[doc = "Aux 2, -1 .. 1"]
9511 pub aux2: f32,
9512 #[doc = "Aux 3, -1 .. 1"]
9513 pub aux3: f32,
9514 #[doc = "Aux 4, -1 .. 1"]
9515 pub aux4: f32,
9516 #[doc = "System mode."]
9517 pub mode: MavMode,
9518 #[doc = "Navigation mode (MAV_NAV_MODE)"]
9519 pub nav_mode: u8,
9520}
9521impl HIL_CONTROLS_DATA {
9522 pub const ENCODED_LEN: usize = 42usize;
9523 pub const DEFAULT: Self = Self {
9524 time_usec: 0_u64,
9525 roll_ailerons: 0.0_f32,
9526 pitch_elevator: 0.0_f32,
9527 yaw_rudder: 0.0_f32,
9528 throttle: 0.0_f32,
9529 aux1: 0.0_f32,
9530 aux2: 0.0_f32,
9531 aux3: 0.0_f32,
9532 aux4: 0.0_f32,
9533 mode: MavMode::DEFAULT,
9534 nav_mode: 0_u8,
9535 };
9536 #[cfg(feature = "arbitrary")]
9537 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9538 use arbitrary::{Arbitrary, Unstructured};
9539 let mut buf = [0u8; 1024];
9540 rng.fill_bytes(&mut buf);
9541 let mut unstructured = Unstructured::new(&buf);
9542 Self::arbitrary(&mut unstructured).unwrap_or_default()
9543 }
9544}
9545impl Default for HIL_CONTROLS_DATA {
9546 fn default() -> Self {
9547 Self::DEFAULT.clone()
9548 }
9549}
9550impl MessageData for HIL_CONTROLS_DATA {
9551 type Message = MavMessage;
9552 const ID: u32 = 91u32;
9553 const NAME: &'static str = "HIL_CONTROLS";
9554 const EXTRA_CRC: u8 = 63u8;
9555 const ENCODED_LEN: usize = 42usize;
9556 fn deser(
9557 _version: MavlinkVersion,
9558 __input: &[u8],
9559 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9560 let avail_len = __input.len();
9561 let mut payload_buf = [0; Self::ENCODED_LEN];
9562 let mut buf = if avail_len < Self::ENCODED_LEN {
9563 payload_buf[0..avail_len].copy_from_slice(__input);
9564 Bytes::new(&payload_buf)
9565 } else {
9566 Bytes::new(__input)
9567 };
9568 let mut __struct = Self::default();
9569 __struct.time_usec = buf.get_u64_le();
9570 __struct.roll_ailerons = buf.get_f32_le();
9571 __struct.pitch_elevator = buf.get_f32_le();
9572 __struct.yaw_rudder = buf.get_f32_le();
9573 __struct.throttle = buf.get_f32_le();
9574 __struct.aux1 = buf.get_f32_le();
9575 __struct.aux2 = buf.get_f32_le();
9576 __struct.aux3 = buf.get_f32_le();
9577 __struct.aux4 = buf.get_f32_le();
9578 let tmp = buf.get_u8();
9579 __struct.mode =
9580 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9581 enum_type: "MavMode",
9582 value: tmp as u32,
9583 })?;
9584 __struct.nav_mode = buf.get_u8();
9585 Ok(__struct)
9586 }
9587 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9588 let mut __tmp = BytesMut::new(bytes);
9589 #[allow(clippy::absurd_extreme_comparisons)]
9590 #[allow(unused_comparisons)]
9591 if __tmp.remaining() < Self::ENCODED_LEN {
9592 panic!(
9593 "buffer is too small (need {} bytes, but got {})",
9594 Self::ENCODED_LEN,
9595 __tmp.remaining(),
9596 )
9597 }
9598 __tmp.put_u64_le(self.time_usec);
9599 __tmp.put_f32_le(self.roll_ailerons);
9600 __tmp.put_f32_le(self.pitch_elevator);
9601 __tmp.put_f32_le(self.yaw_rudder);
9602 __tmp.put_f32_le(self.throttle);
9603 __tmp.put_f32_le(self.aux1);
9604 __tmp.put_f32_le(self.aux2);
9605 __tmp.put_f32_le(self.aux3);
9606 __tmp.put_f32_le(self.aux4);
9607 __tmp.put_u8(self.mode as u8);
9608 __tmp.put_u8(self.nav_mode);
9609 if matches!(version, MavlinkVersion::V2) {
9610 let len = __tmp.len();
9611 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9612 } else {
9613 __tmp.len()
9614 }
9615 }
9616}
9617#[doc = "id: 286"]
9618#[doc = "Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis."]
9619#[derive(Debug, Clone, PartialEq)]
9620#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9621#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9622pub struct AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
9623 #[doc = "Timestamp (time since system boot)."]
9624 pub time_boot_us: u64,
9625 #[doc = "Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention)."]
9626 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9627 pub q: [f32; 4],
9628 #[doc = "Estimated delay of the attitude data. 0 if unknown."]
9629 pub q_estimated_delay_us: u32,
9630 #[doc = "X Speed in NED (North, East, Down). NAN if unknown."]
9631 pub vx: f32,
9632 #[doc = "Y Speed in NED (North, East, Down). NAN if unknown."]
9633 pub vy: f32,
9634 #[doc = "Z Speed in NED (North, East, Down). NAN if unknown."]
9635 pub vz: f32,
9636 #[doc = "Estimated delay of the speed data. 0 if unknown."]
9637 pub v_estimated_delay_us: u32,
9638 #[doc = "Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing."]
9639 pub feed_forward_angular_velocity_z: f32,
9640 #[doc = "Bitmap indicating which estimator outputs are valid."]
9641 pub estimator_status: EstimatorStatusFlags,
9642 #[doc = "System ID"]
9643 pub target_system: u8,
9644 #[doc = "Component ID"]
9645 pub target_component: u8,
9646 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
9647 pub landed_state: MavLandedState,
9648 #[doc = "Z component of angular velocity in NED (North, East, Down). NaN if unknown."]
9649 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9650 pub angular_velocity_z: f32,
9651}
9652impl AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
9653 pub const ENCODED_LEN: usize = 57usize;
9654 pub const DEFAULT: Self = Self {
9655 time_boot_us: 0_u64,
9656 q: [0.0_f32; 4usize],
9657 q_estimated_delay_us: 0_u32,
9658 vx: 0.0_f32,
9659 vy: 0.0_f32,
9660 vz: 0.0_f32,
9661 v_estimated_delay_us: 0_u32,
9662 feed_forward_angular_velocity_z: 0.0_f32,
9663 estimator_status: EstimatorStatusFlags::DEFAULT,
9664 target_system: 0_u8,
9665 target_component: 0_u8,
9666 landed_state: MavLandedState::DEFAULT,
9667 angular_velocity_z: 0.0_f32,
9668 };
9669 #[cfg(feature = "arbitrary")]
9670 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9671 use arbitrary::{Arbitrary, Unstructured};
9672 let mut buf = [0u8; 1024];
9673 rng.fill_bytes(&mut buf);
9674 let mut unstructured = Unstructured::new(&buf);
9675 Self::arbitrary(&mut unstructured).unwrap_or_default()
9676 }
9677}
9678impl Default for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
9679 fn default() -> Self {
9680 Self::DEFAULT.clone()
9681 }
9682}
9683impl MessageData for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
9684 type Message = MavMessage;
9685 const ID: u32 = 286u32;
9686 const NAME: &'static str = "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE";
9687 const EXTRA_CRC: u8 = 210u8;
9688 const ENCODED_LEN: usize = 57usize;
9689 fn deser(
9690 _version: MavlinkVersion,
9691 __input: &[u8],
9692 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9693 let avail_len = __input.len();
9694 let mut payload_buf = [0; Self::ENCODED_LEN];
9695 let mut buf = if avail_len < Self::ENCODED_LEN {
9696 payload_buf[0..avail_len].copy_from_slice(__input);
9697 Bytes::new(&payload_buf)
9698 } else {
9699 Bytes::new(__input)
9700 };
9701 let mut __struct = Self::default();
9702 __struct.time_boot_us = buf.get_u64_le();
9703 for v in &mut __struct.q {
9704 let val = buf.get_f32_le();
9705 *v = val;
9706 }
9707 __struct.q_estimated_delay_us = buf.get_u32_le();
9708 __struct.vx = buf.get_f32_le();
9709 __struct.vy = buf.get_f32_le();
9710 __struct.vz = buf.get_f32_le();
9711 __struct.v_estimated_delay_us = buf.get_u32_le();
9712 __struct.feed_forward_angular_velocity_z = buf.get_f32_le();
9713 let tmp = buf.get_u16_le();
9714 __struct.estimator_status = EstimatorStatusFlags::from_bits(
9715 tmp & EstimatorStatusFlags::all().bits(),
9716 )
9717 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
9718 flag_type: "EstimatorStatusFlags",
9719 value: tmp as u32,
9720 })?;
9721 __struct.target_system = buf.get_u8();
9722 __struct.target_component = buf.get_u8();
9723 let tmp = buf.get_u8();
9724 __struct.landed_state =
9725 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9726 enum_type: "MavLandedState",
9727 value: tmp as u32,
9728 })?;
9729 __struct.angular_velocity_z = buf.get_f32_le();
9730 Ok(__struct)
9731 }
9732 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9733 let mut __tmp = BytesMut::new(bytes);
9734 #[allow(clippy::absurd_extreme_comparisons)]
9735 #[allow(unused_comparisons)]
9736 if __tmp.remaining() < Self::ENCODED_LEN {
9737 panic!(
9738 "buffer is too small (need {} bytes, but got {})",
9739 Self::ENCODED_LEN,
9740 __tmp.remaining(),
9741 )
9742 }
9743 __tmp.put_u64_le(self.time_boot_us);
9744 for val in &self.q {
9745 __tmp.put_f32_le(*val);
9746 }
9747 __tmp.put_u32_le(self.q_estimated_delay_us);
9748 __tmp.put_f32_le(self.vx);
9749 __tmp.put_f32_le(self.vy);
9750 __tmp.put_f32_le(self.vz);
9751 __tmp.put_u32_le(self.v_estimated_delay_us);
9752 __tmp.put_f32_le(self.feed_forward_angular_velocity_z);
9753 __tmp.put_u16_le(self.estimator_status.bits());
9754 __tmp.put_u8(self.target_system);
9755 __tmp.put_u8(self.target_component);
9756 __tmp.put_u8(self.landed_state as u8);
9757 __tmp.put_f32_le(self.angular_velocity_z);
9758 if matches!(version, MavlinkVersion::V2) {
9759 let len = __tmp.len();
9760 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9761 } else {
9762 __tmp.len()
9763 }
9764 }
9765}
9766#[doc = "id: 102"]
9767#[doc = "Local position/attitude estimate from a vision source."]
9768#[derive(Debug, Clone, PartialEq)]
9769#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9770#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9771pub struct VISION_POSITION_ESTIMATE_DATA {
9772 #[doc = "Timestamp (UNIX time or time since system boot)"]
9773 pub usec: u64,
9774 #[doc = "Local X position"]
9775 pub x: f32,
9776 #[doc = "Local Y position"]
9777 pub y: f32,
9778 #[doc = "Local Z position"]
9779 pub z: f32,
9780 #[doc = "Roll angle"]
9781 pub roll: f32,
9782 #[doc = "Pitch angle"]
9783 pub pitch: f32,
9784 #[doc = "Yaw angle"]
9785 pub yaw: f32,
9786 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
9787 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9788 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9789 pub covariance: [f32; 21],
9790 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
9791 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9792 pub reset_counter: u8,
9793}
9794impl VISION_POSITION_ESTIMATE_DATA {
9795 pub const ENCODED_LEN: usize = 117usize;
9796 pub const DEFAULT: Self = Self {
9797 usec: 0_u64,
9798 x: 0.0_f32,
9799 y: 0.0_f32,
9800 z: 0.0_f32,
9801 roll: 0.0_f32,
9802 pitch: 0.0_f32,
9803 yaw: 0.0_f32,
9804 covariance: [0.0_f32; 21usize],
9805 reset_counter: 0_u8,
9806 };
9807 #[cfg(feature = "arbitrary")]
9808 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9809 use arbitrary::{Arbitrary, Unstructured};
9810 let mut buf = [0u8; 1024];
9811 rng.fill_bytes(&mut buf);
9812 let mut unstructured = Unstructured::new(&buf);
9813 Self::arbitrary(&mut unstructured).unwrap_or_default()
9814 }
9815}
9816impl Default for VISION_POSITION_ESTIMATE_DATA {
9817 fn default() -> Self {
9818 Self::DEFAULT.clone()
9819 }
9820}
9821impl MessageData for VISION_POSITION_ESTIMATE_DATA {
9822 type Message = MavMessage;
9823 const ID: u32 = 102u32;
9824 const NAME: &'static str = "VISION_POSITION_ESTIMATE";
9825 const EXTRA_CRC: u8 = 158u8;
9826 const ENCODED_LEN: usize = 117usize;
9827 fn deser(
9828 _version: MavlinkVersion,
9829 __input: &[u8],
9830 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9831 let avail_len = __input.len();
9832 let mut payload_buf = [0; Self::ENCODED_LEN];
9833 let mut buf = if avail_len < Self::ENCODED_LEN {
9834 payload_buf[0..avail_len].copy_from_slice(__input);
9835 Bytes::new(&payload_buf)
9836 } else {
9837 Bytes::new(__input)
9838 };
9839 let mut __struct = Self::default();
9840 __struct.usec = buf.get_u64_le();
9841 __struct.x = buf.get_f32_le();
9842 __struct.y = buf.get_f32_le();
9843 __struct.z = buf.get_f32_le();
9844 __struct.roll = buf.get_f32_le();
9845 __struct.pitch = buf.get_f32_le();
9846 __struct.yaw = buf.get_f32_le();
9847 for v in &mut __struct.covariance {
9848 let val = buf.get_f32_le();
9849 *v = val;
9850 }
9851 __struct.reset_counter = buf.get_u8();
9852 Ok(__struct)
9853 }
9854 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9855 let mut __tmp = BytesMut::new(bytes);
9856 #[allow(clippy::absurd_extreme_comparisons)]
9857 #[allow(unused_comparisons)]
9858 if __tmp.remaining() < Self::ENCODED_LEN {
9859 panic!(
9860 "buffer is too small (need {} bytes, but got {})",
9861 Self::ENCODED_LEN,
9862 __tmp.remaining(),
9863 )
9864 }
9865 __tmp.put_u64_le(self.usec);
9866 __tmp.put_f32_le(self.x);
9867 __tmp.put_f32_le(self.y);
9868 __tmp.put_f32_le(self.z);
9869 __tmp.put_f32_le(self.roll);
9870 __tmp.put_f32_le(self.pitch);
9871 __tmp.put_f32_le(self.yaw);
9872 for val in &self.covariance {
9873 __tmp.put_f32_le(*val);
9874 }
9875 __tmp.put_u8(self.reset_counter);
9876 if matches!(version, MavlinkVersion::V2) {
9877 let len = __tmp.len();
9878 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9879 } else {
9880 __tmp.len()
9881 }
9882 }
9883}
9884#[doc = "id: 80"]
9885#[doc = "Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
9886#[derive(Debug, Clone, PartialEq)]
9887#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9888#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9889pub struct COMMAND_CANCEL_DATA {
9890 #[doc = "Command ID (of command to cancel)."]
9891 pub command: MavCmd,
9892 #[doc = "System executing long running command. Should not be broadcast (0)."]
9893 pub target_system: u8,
9894 #[doc = "Component executing long running command."]
9895 pub target_component: u8,
9896}
9897impl COMMAND_CANCEL_DATA {
9898 pub const ENCODED_LEN: usize = 4usize;
9899 pub const DEFAULT: Self = Self {
9900 command: MavCmd::DEFAULT,
9901 target_system: 0_u8,
9902 target_component: 0_u8,
9903 };
9904 #[cfg(feature = "arbitrary")]
9905 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9906 use arbitrary::{Arbitrary, Unstructured};
9907 let mut buf = [0u8; 1024];
9908 rng.fill_bytes(&mut buf);
9909 let mut unstructured = Unstructured::new(&buf);
9910 Self::arbitrary(&mut unstructured).unwrap_or_default()
9911 }
9912}
9913impl Default for COMMAND_CANCEL_DATA {
9914 fn default() -> Self {
9915 Self::DEFAULT.clone()
9916 }
9917}
9918impl MessageData for COMMAND_CANCEL_DATA {
9919 type Message = MavMessage;
9920 const ID: u32 = 80u32;
9921 const NAME: &'static str = "COMMAND_CANCEL";
9922 const EXTRA_CRC: u8 = 14u8;
9923 const ENCODED_LEN: usize = 4usize;
9924 fn deser(
9925 _version: MavlinkVersion,
9926 __input: &[u8],
9927 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9928 let avail_len = __input.len();
9929 let mut payload_buf = [0; Self::ENCODED_LEN];
9930 let mut buf = if avail_len < Self::ENCODED_LEN {
9931 payload_buf[0..avail_len].copy_from_slice(__input);
9932 Bytes::new(&payload_buf)
9933 } else {
9934 Bytes::new(__input)
9935 };
9936 let mut __struct = Self::default();
9937 let tmp = buf.get_u16_le();
9938 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
9939 ::mavlink_core::error::ParserError::InvalidEnum {
9940 enum_type: "MavCmd",
9941 value: tmp as u32,
9942 },
9943 )?;
9944 __struct.target_system = buf.get_u8();
9945 __struct.target_component = buf.get_u8();
9946 Ok(__struct)
9947 }
9948 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9949 let mut __tmp = BytesMut::new(bytes);
9950 #[allow(clippy::absurd_extreme_comparisons)]
9951 #[allow(unused_comparisons)]
9952 if __tmp.remaining() < Self::ENCODED_LEN {
9953 panic!(
9954 "buffer is too small (need {} bytes, but got {})",
9955 Self::ENCODED_LEN,
9956 __tmp.remaining(),
9957 )
9958 }
9959 __tmp.put_u16_le(self.command as u16);
9960 __tmp.put_u8(self.target_system);
9961 __tmp.put_u8(self.target_component);
9962 if matches!(version, MavlinkVersion::V2) {
9963 let len = __tmp.len();
9964 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9965 } else {
9966 __tmp.len()
9967 }
9968 }
9969}
9970#[doc = "id: 260"]
9971#[doc = "Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
9972#[derive(Debug, Clone, PartialEq)]
9973#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9974#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9975pub struct CAMERA_SETTINGS_DATA {
9976 #[doc = "Timestamp (time since system boot)."]
9977 pub time_boot_ms: u32,
9978 #[doc = "Camera mode"]
9979 pub mode_id: CameraMode,
9980 #[doc = "Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
9981 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9982 pub zoomLevel: f32,
9983 #[doc = "Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
9984 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9985 pub focusLevel: f32,
9986 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
9987 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9988 pub camera_device_id: u8,
9989}
9990impl CAMERA_SETTINGS_DATA {
9991 pub const ENCODED_LEN: usize = 14usize;
9992 pub const DEFAULT: Self = Self {
9993 time_boot_ms: 0_u32,
9994 mode_id: CameraMode::DEFAULT,
9995 zoomLevel: 0.0_f32,
9996 focusLevel: 0.0_f32,
9997 camera_device_id: 0_u8,
9998 };
9999 #[cfg(feature = "arbitrary")]
10000 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10001 use arbitrary::{Arbitrary, Unstructured};
10002 let mut buf = [0u8; 1024];
10003 rng.fill_bytes(&mut buf);
10004 let mut unstructured = Unstructured::new(&buf);
10005 Self::arbitrary(&mut unstructured).unwrap_or_default()
10006 }
10007}
10008impl Default for CAMERA_SETTINGS_DATA {
10009 fn default() -> Self {
10010 Self::DEFAULT.clone()
10011 }
10012}
10013impl MessageData for CAMERA_SETTINGS_DATA {
10014 type Message = MavMessage;
10015 const ID: u32 = 260u32;
10016 const NAME: &'static str = "CAMERA_SETTINGS";
10017 const EXTRA_CRC: u8 = 146u8;
10018 const ENCODED_LEN: usize = 14usize;
10019 fn deser(
10020 _version: MavlinkVersion,
10021 __input: &[u8],
10022 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10023 let avail_len = __input.len();
10024 let mut payload_buf = [0; Self::ENCODED_LEN];
10025 let mut buf = if avail_len < Self::ENCODED_LEN {
10026 payload_buf[0..avail_len].copy_from_slice(__input);
10027 Bytes::new(&payload_buf)
10028 } else {
10029 Bytes::new(__input)
10030 };
10031 let mut __struct = Self::default();
10032 __struct.time_boot_ms = buf.get_u32_le();
10033 let tmp = buf.get_u8();
10034 __struct.mode_id =
10035 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10036 enum_type: "CameraMode",
10037 value: tmp as u32,
10038 })?;
10039 __struct.zoomLevel = buf.get_f32_le();
10040 __struct.focusLevel = buf.get_f32_le();
10041 __struct.camera_device_id = buf.get_u8();
10042 Ok(__struct)
10043 }
10044 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10045 let mut __tmp = BytesMut::new(bytes);
10046 #[allow(clippy::absurd_extreme_comparisons)]
10047 #[allow(unused_comparisons)]
10048 if __tmp.remaining() < Self::ENCODED_LEN {
10049 panic!(
10050 "buffer is too small (need {} bytes, but got {})",
10051 Self::ENCODED_LEN,
10052 __tmp.remaining(),
10053 )
10054 }
10055 __tmp.put_u32_le(self.time_boot_ms);
10056 __tmp.put_u8(self.mode_id as u8);
10057 __tmp.put_f32_le(self.zoomLevel);
10058 __tmp.put_f32_le(self.focusLevel);
10059 __tmp.put_u8(self.camera_device_id);
10060 if matches!(version, MavlinkVersion::V2) {
10061 let len = __tmp.len();
10062 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10063 } else {
10064 __tmp.len()
10065 }
10066 }
10067}
10068#[doc = "id: 25"]
10069#[doc = "The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites."]
10070#[derive(Debug, Clone, PartialEq)]
10071#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10072#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10073pub struct GPS_STATUS_DATA {
10074 #[doc = "Number of satellites visible"]
10075 pub satellites_visible: u8,
10076 #[doc = "Global satellite ID"]
10077 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10078 pub satellite_prn: [u8; 20],
10079 #[doc = "0: Satellite not used, 1: used for localization"]
10080 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10081 pub satellite_used: [u8; 20],
10082 #[doc = "Elevation (0: right on top of receiver, 90: on the horizon) of satellite"]
10083 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10084 pub satellite_elevation: [u8; 20],
10085 #[doc = "Direction of satellite, 0: 0 deg, 255: 360 deg."]
10086 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10087 pub satellite_azimuth: [u8; 20],
10088 #[doc = "Signal to noise ratio of satellite"]
10089 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10090 pub satellite_snr: [u8; 20],
10091}
10092impl GPS_STATUS_DATA {
10093 pub const ENCODED_LEN: usize = 101usize;
10094 pub const DEFAULT: Self = Self {
10095 satellites_visible: 0_u8,
10096 satellite_prn: [0_u8; 20usize],
10097 satellite_used: [0_u8; 20usize],
10098 satellite_elevation: [0_u8; 20usize],
10099 satellite_azimuth: [0_u8; 20usize],
10100 satellite_snr: [0_u8; 20usize],
10101 };
10102 #[cfg(feature = "arbitrary")]
10103 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10104 use arbitrary::{Arbitrary, Unstructured};
10105 let mut buf = [0u8; 1024];
10106 rng.fill_bytes(&mut buf);
10107 let mut unstructured = Unstructured::new(&buf);
10108 Self::arbitrary(&mut unstructured).unwrap_or_default()
10109 }
10110}
10111impl Default for GPS_STATUS_DATA {
10112 fn default() -> Self {
10113 Self::DEFAULT.clone()
10114 }
10115}
10116impl MessageData for GPS_STATUS_DATA {
10117 type Message = MavMessage;
10118 const ID: u32 = 25u32;
10119 const NAME: &'static str = "GPS_STATUS";
10120 const EXTRA_CRC: u8 = 23u8;
10121 const ENCODED_LEN: usize = 101usize;
10122 fn deser(
10123 _version: MavlinkVersion,
10124 __input: &[u8],
10125 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10126 let avail_len = __input.len();
10127 let mut payload_buf = [0; Self::ENCODED_LEN];
10128 let mut buf = if avail_len < Self::ENCODED_LEN {
10129 payload_buf[0..avail_len].copy_from_slice(__input);
10130 Bytes::new(&payload_buf)
10131 } else {
10132 Bytes::new(__input)
10133 };
10134 let mut __struct = Self::default();
10135 __struct.satellites_visible = buf.get_u8();
10136 for v in &mut __struct.satellite_prn {
10137 let val = buf.get_u8();
10138 *v = val;
10139 }
10140 for v in &mut __struct.satellite_used {
10141 let val = buf.get_u8();
10142 *v = val;
10143 }
10144 for v in &mut __struct.satellite_elevation {
10145 let val = buf.get_u8();
10146 *v = val;
10147 }
10148 for v in &mut __struct.satellite_azimuth {
10149 let val = buf.get_u8();
10150 *v = val;
10151 }
10152 for v in &mut __struct.satellite_snr {
10153 let val = buf.get_u8();
10154 *v = val;
10155 }
10156 Ok(__struct)
10157 }
10158 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10159 let mut __tmp = BytesMut::new(bytes);
10160 #[allow(clippy::absurd_extreme_comparisons)]
10161 #[allow(unused_comparisons)]
10162 if __tmp.remaining() < Self::ENCODED_LEN {
10163 panic!(
10164 "buffer is too small (need {} bytes, but got {})",
10165 Self::ENCODED_LEN,
10166 __tmp.remaining(),
10167 )
10168 }
10169 __tmp.put_u8(self.satellites_visible);
10170 for val in &self.satellite_prn {
10171 __tmp.put_u8(*val);
10172 }
10173 for val in &self.satellite_used {
10174 __tmp.put_u8(*val);
10175 }
10176 for val in &self.satellite_elevation {
10177 __tmp.put_u8(*val);
10178 }
10179 for val in &self.satellite_azimuth {
10180 __tmp.put_u8(*val);
10181 }
10182 for val in &self.satellite_snr {
10183 __tmp.put_u8(*val);
10184 }
10185 if matches!(version, MavlinkVersion::V2) {
10186 let len = __tmp.len();
10187 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10188 } else {
10189 __tmp.len()
10190 }
10191 }
10192}
10193#[doc = "id: 30"]
10194#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic)."]
10195#[derive(Debug, Clone, PartialEq)]
10196#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10197#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10198pub struct ATTITUDE_DATA {
10199 #[doc = "Timestamp (time since system boot)."]
10200 pub time_boot_ms: u32,
10201 #[doc = "Roll angle (-pi..+pi)"]
10202 pub roll: f32,
10203 #[doc = "Pitch angle (-pi..+pi)"]
10204 pub pitch: f32,
10205 #[doc = "Yaw angle (-pi..+pi)"]
10206 pub yaw: f32,
10207 #[doc = "Roll angular speed"]
10208 pub rollspeed: f32,
10209 #[doc = "Pitch angular speed"]
10210 pub pitchspeed: f32,
10211 #[doc = "Yaw angular speed"]
10212 pub yawspeed: f32,
10213}
10214impl ATTITUDE_DATA {
10215 pub const ENCODED_LEN: usize = 28usize;
10216 pub const DEFAULT: Self = Self {
10217 time_boot_ms: 0_u32,
10218 roll: 0.0_f32,
10219 pitch: 0.0_f32,
10220 yaw: 0.0_f32,
10221 rollspeed: 0.0_f32,
10222 pitchspeed: 0.0_f32,
10223 yawspeed: 0.0_f32,
10224 };
10225 #[cfg(feature = "arbitrary")]
10226 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10227 use arbitrary::{Arbitrary, Unstructured};
10228 let mut buf = [0u8; 1024];
10229 rng.fill_bytes(&mut buf);
10230 let mut unstructured = Unstructured::new(&buf);
10231 Self::arbitrary(&mut unstructured).unwrap_or_default()
10232 }
10233}
10234impl Default for ATTITUDE_DATA {
10235 fn default() -> Self {
10236 Self::DEFAULT.clone()
10237 }
10238}
10239impl MessageData for ATTITUDE_DATA {
10240 type Message = MavMessage;
10241 const ID: u32 = 30u32;
10242 const NAME: &'static str = "ATTITUDE";
10243 const EXTRA_CRC: u8 = 39u8;
10244 const ENCODED_LEN: usize = 28usize;
10245 fn deser(
10246 _version: MavlinkVersion,
10247 __input: &[u8],
10248 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10249 let avail_len = __input.len();
10250 let mut payload_buf = [0; Self::ENCODED_LEN];
10251 let mut buf = if avail_len < Self::ENCODED_LEN {
10252 payload_buf[0..avail_len].copy_from_slice(__input);
10253 Bytes::new(&payload_buf)
10254 } else {
10255 Bytes::new(__input)
10256 };
10257 let mut __struct = Self::default();
10258 __struct.time_boot_ms = buf.get_u32_le();
10259 __struct.roll = buf.get_f32_le();
10260 __struct.pitch = buf.get_f32_le();
10261 __struct.yaw = buf.get_f32_le();
10262 __struct.rollspeed = buf.get_f32_le();
10263 __struct.pitchspeed = buf.get_f32_le();
10264 __struct.yawspeed = buf.get_f32_le();
10265 Ok(__struct)
10266 }
10267 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10268 let mut __tmp = BytesMut::new(bytes);
10269 #[allow(clippy::absurd_extreme_comparisons)]
10270 #[allow(unused_comparisons)]
10271 if __tmp.remaining() < Self::ENCODED_LEN {
10272 panic!(
10273 "buffer is too small (need {} bytes, but got {})",
10274 Self::ENCODED_LEN,
10275 __tmp.remaining(),
10276 )
10277 }
10278 __tmp.put_u32_le(self.time_boot_ms);
10279 __tmp.put_f32_le(self.roll);
10280 __tmp.put_f32_le(self.pitch);
10281 __tmp.put_f32_le(self.yaw);
10282 __tmp.put_f32_le(self.rollspeed);
10283 __tmp.put_f32_le(self.pitchspeed);
10284 __tmp.put_f32_le(self.yawspeed);
10285 if matches!(version, MavlinkVersion::V2) {
10286 let len = __tmp.len();
10287 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10288 } else {
10289 __tmp.len()
10290 }
10291 }
10292}
10293#[doc = "id: 131"]
10294#[doc = "Data packet for images sent using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
10295#[derive(Debug, Clone, PartialEq)]
10296#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10297#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10298pub struct ENCAPSULATED_DATA_DATA {
10299 #[doc = "sequence number (starting with 0 on every transmission)"]
10300 pub seqnr: u16,
10301 #[doc = "image data bytes"]
10302 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10303 pub data: [u8; 253],
10304}
10305impl ENCAPSULATED_DATA_DATA {
10306 pub const ENCODED_LEN: usize = 255usize;
10307 pub const DEFAULT: Self = Self {
10308 seqnr: 0_u16,
10309 data: [0_u8; 253usize],
10310 };
10311 #[cfg(feature = "arbitrary")]
10312 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10313 use arbitrary::{Arbitrary, Unstructured};
10314 let mut buf = [0u8; 1024];
10315 rng.fill_bytes(&mut buf);
10316 let mut unstructured = Unstructured::new(&buf);
10317 Self::arbitrary(&mut unstructured).unwrap_or_default()
10318 }
10319}
10320impl Default for ENCAPSULATED_DATA_DATA {
10321 fn default() -> Self {
10322 Self::DEFAULT.clone()
10323 }
10324}
10325impl MessageData for ENCAPSULATED_DATA_DATA {
10326 type Message = MavMessage;
10327 const ID: u32 = 131u32;
10328 const NAME: &'static str = "ENCAPSULATED_DATA";
10329 const EXTRA_CRC: u8 = 223u8;
10330 const ENCODED_LEN: usize = 255usize;
10331 fn deser(
10332 _version: MavlinkVersion,
10333 __input: &[u8],
10334 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10335 let avail_len = __input.len();
10336 let mut payload_buf = [0; Self::ENCODED_LEN];
10337 let mut buf = if avail_len < Self::ENCODED_LEN {
10338 payload_buf[0..avail_len].copy_from_slice(__input);
10339 Bytes::new(&payload_buf)
10340 } else {
10341 Bytes::new(__input)
10342 };
10343 let mut __struct = Self::default();
10344 __struct.seqnr = buf.get_u16_le();
10345 for v in &mut __struct.data {
10346 let val = buf.get_u8();
10347 *v = val;
10348 }
10349 Ok(__struct)
10350 }
10351 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10352 let mut __tmp = BytesMut::new(bytes);
10353 #[allow(clippy::absurd_extreme_comparisons)]
10354 #[allow(unused_comparisons)]
10355 if __tmp.remaining() < Self::ENCODED_LEN {
10356 panic!(
10357 "buffer is too small (need {} bytes, but got {})",
10358 Self::ENCODED_LEN,
10359 __tmp.remaining(),
10360 )
10361 }
10362 __tmp.put_u16_le(self.seqnr);
10363 for val in &self.data {
10364 __tmp.put_u8(*val);
10365 }
10366 if matches!(version, MavlinkVersion::V2) {
10367 let len = __tmp.len();
10368 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10369 } else {
10370 __tmp.len()
10371 }
10372 }
10373}
10374#[doc = "id: 334"]
10375#[doc = "Report current used cellular network status."]
10376#[derive(Debug, Clone, PartialEq)]
10377#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10378#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10379pub struct CELLULAR_STATUS_DATA {
10380 #[doc = "Mobile country code. If unknown, set to UINT16_MAX"]
10381 pub mcc: u16,
10382 #[doc = "Mobile network code. If unknown, set to UINT16_MAX"]
10383 pub mnc: u16,
10384 #[doc = "Location area code. If unknown, set to 0"]
10385 pub lac: u16,
10386 #[doc = "Cellular modem status"]
10387 pub status: CellularStatusFlag,
10388 #[doc = "Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED"]
10389 pub failure_reason: CellularNetworkFailedReason,
10390 #[doc = "Cellular network radio type: gsm, cdma, lte..."]
10391 pub mavtype: CellularNetworkRadioType,
10392 #[doc = "Signal quality in percent. If unknown, set to UINT8_MAX"]
10393 pub quality: u8,
10394}
10395impl CELLULAR_STATUS_DATA {
10396 pub const ENCODED_LEN: usize = 10usize;
10397 pub const DEFAULT: Self = Self {
10398 mcc: 0_u16,
10399 mnc: 0_u16,
10400 lac: 0_u16,
10401 status: CellularStatusFlag::DEFAULT,
10402 failure_reason: CellularNetworkFailedReason::DEFAULT,
10403 mavtype: CellularNetworkRadioType::DEFAULT,
10404 quality: 0_u8,
10405 };
10406 #[cfg(feature = "arbitrary")]
10407 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10408 use arbitrary::{Arbitrary, Unstructured};
10409 let mut buf = [0u8; 1024];
10410 rng.fill_bytes(&mut buf);
10411 let mut unstructured = Unstructured::new(&buf);
10412 Self::arbitrary(&mut unstructured).unwrap_or_default()
10413 }
10414}
10415impl Default for CELLULAR_STATUS_DATA {
10416 fn default() -> Self {
10417 Self::DEFAULT.clone()
10418 }
10419}
10420impl MessageData for CELLULAR_STATUS_DATA {
10421 type Message = MavMessage;
10422 const ID: u32 = 334u32;
10423 const NAME: &'static str = "CELLULAR_STATUS";
10424 const EXTRA_CRC: u8 = 72u8;
10425 const ENCODED_LEN: usize = 10usize;
10426 fn deser(
10427 _version: MavlinkVersion,
10428 __input: &[u8],
10429 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10430 let avail_len = __input.len();
10431 let mut payload_buf = [0; Self::ENCODED_LEN];
10432 let mut buf = if avail_len < Self::ENCODED_LEN {
10433 payload_buf[0..avail_len].copy_from_slice(__input);
10434 Bytes::new(&payload_buf)
10435 } else {
10436 Bytes::new(__input)
10437 };
10438 let mut __struct = Self::default();
10439 __struct.mcc = buf.get_u16_le();
10440 __struct.mnc = buf.get_u16_le();
10441 __struct.lac = buf.get_u16_le();
10442 let tmp = buf.get_u8();
10443 __struct.status =
10444 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10445 enum_type: "CellularStatusFlag",
10446 value: tmp as u32,
10447 })?;
10448 let tmp = buf.get_u8();
10449 __struct.failure_reason =
10450 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10451 enum_type: "CellularNetworkFailedReason",
10452 value: tmp as u32,
10453 })?;
10454 let tmp = buf.get_u8();
10455 __struct.mavtype =
10456 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10457 enum_type: "CellularNetworkRadioType",
10458 value: tmp as u32,
10459 })?;
10460 __struct.quality = buf.get_u8();
10461 Ok(__struct)
10462 }
10463 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10464 let mut __tmp = BytesMut::new(bytes);
10465 #[allow(clippy::absurd_extreme_comparisons)]
10466 #[allow(unused_comparisons)]
10467 if __tmp.remaining() < Self::ENCODED_LEN {
10468 panic!(
10469 "buffer is too small (need {} bytes, but got {})",
10470 Self::ENCODED_LEN,
10471 __tmp.remaining(),
10472 )
10473 }
10474 __tmp.put_u16_le(self.mcc);
10475 __tmp.put_u16_le(self.mnc);
10476 __tmp.put_u16_le(self.lac);
10477 __tmp.put_u8(self.status as u8);
10478 __tmp.put_u8(self.failure_reason as u8);
10479 __tmp.put_u8(self.mavtype as u8);
10480 __tmp.put_u8(self.quality);
10481 if matches!(version, MavlinkVersion::V2) {
10482 let len = __tmp.len();
10483 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10484 } else {
10485 __tmp.len()
10486 }
10487 }
10488}
10489#[doc = "id: 291"]
10490#[doc = "ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer)."]
10491#[derive(Debug, Clone, PartialEq)]
10492#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10493#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10494pub struct ESC_STATUS_DATA {
10495 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
10496 pub time_usec: u64,
10497 #[doc = "Reported motor RPM from each ESC (negative for reverse rotation)."]
10498 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10499 pub rpm: [i32; 4],
10500 #[doc = "Voltage measured from each ESC."]
10501 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10502 pub voltage: [f32; 4],
10503 #[doc = "Current measured from each ESC."]
10504 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10505 pub current: [f32; 4],
10506 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
10507 pub index: u8,
10508}
10509impl ESC_STATUS_DATA {
10510 pub const ENCODED_LEN: usize = 57usize;
10511 pub const DEFAULT: Self = Self {
10512 time_usec: 0_u64,
10513 rpm: [0_i32; 4usize],
10514 voltage: [0.0_f32; 4usize],
10515 current: [0.0_f32; 4usize],
10516 index: 0_u8,
10517 };
10518 #[cfg(feature = "arbitrary")]
10519 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10520 use arbitrary::{Arbitrary, Unstructured};
10521 let mut buf = [0u8; 1024];
10522 rng.fill_bytes(&mut buf);
10523 let mut unstructured = Unstructured::new(&buf);
10524 Self::arbitrary(&mut unstructured).unwrap_or_default()
10525 }
10526}
10527impl Default for ESC_STATUS_DATA {
10528 fn default() -> Self {
10529 Self::DEFAULT.clone()
10530 }
10531}
10532impl MessageData for ESC_STATUS_DATA {
10533 type Message = MavMessage;
10534 const ID: u32 = 291u32;
10535 const NAME: &'static str = "ESC_STATUS";
10536 const EXTRA_CRC: u8 = 10u8;
10537 const ENCODED_LEN: usize = 57usize;
10538 fn deser(
10539 _version: MavlinkVersion,
10540 __input: &[u8],
10541 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10542 let avail_len = __input.len();
10543 let mut payload_buf = [0; Self::ENCODED_LEN];
10544 let mut buf = if avail_len < Self::ENCODED_LEN {
10545 payload_buf[0..avail_len].copy_from_slice(__input);
10546 Bytes::new(&payload_buf)
10547 } else {
10548 Bytes::new(__input)
10549 };
10550 let mut __struct = Self::default();
10551 __struct.time_usec = buf.get_u64_le();
10552 for v in &mut __struct.rpm {
10553 let val = buf.get_i32_le();
10554 *v = val;
10555 }
10556 for v in &mut __struct.voltage {
10557 let val = buf.get_f32_le();
10558 *v = val;
10559 }
10560 for v in &mut __struct.current {
10561 let val = buf.get_f32_le();
10562 *v = val;
10563 }
10564 __struct.index = buf.get_u8();
10565 Ok(__struct)
10566 }
10567 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10568 let mut __tmp = BytesMut::new(bytes);
10569 #[allow(clippy::absurd_extreme_comparisons)]
10570 #[allow(unused_comparisons)]
10571 if __tmp.remaining() < Self::ENCODED_LEN {
10572 panic!(
10573 "buffer is too small (need {} bytes, but got {})",
10574 Self::ENCODED_LEN,
10575 __tmp.remaining(),
10576 )
10577 }
10578 __tmp.put_u64_le(self.time_usec);
10579 for val in &self.rpm {
10580 __tmp.put_i32_le(*val);
10581 }
10582 for val in &self.voltage {
10583 __tmp.put_f32_le(*val);
10584 }
10585 for val in &self.current {
10586 __tmp.put_f32_le(*val);
10587 }
10588 __tmp.put_u8(self.index);
10589 if matches!(version, MavlinkVersion::V2) {
10590 let len = __tmp.len();
10591 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10592 } else {
10593 __tmp.len()
10594 }
10595 }
10596}
10597#[doc = "id: 27"]
10598#[doc = "The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging."]
10599#[derive(Debug, Clone, PartialEq)]
10600#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10601#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10602pub struct RAW_IMU_DATA {
10603 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
10604 pub time_usec: u64,
10605 #[doc = "X acceleration (raw)"]
10606 pub xacc: i16,
10607 #[doc = "Y acceleration (raw)"]
10608 pub yacc: i16,
10609 #[doc = "Z acceleration (raw)"]
10610 pub zacc: i16,
10611 #[doc = "Angular speed around X axis (raw)"]
10612 pub xgyro: i16,
10613 #[doc = "Angular speed around Y axis (raw)"]
10614 pub ygyro: i16,
10615 #[doc = "Angular speed around Z axis (raw)"]
10616 pub zgyro: i16,
10617 #[doc = "X Magnetic field (raw)"]
10618 pub xmag: i16,
10619 #[doc = "Y Magnetic field (raw)"]
10620 pub ymag: i16,
10621 #[doc = "Z Magnetic field (raw)"]
10622 pub zmag: i16,
10623 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
10624 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10625 pub id: u8,
10626 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
10627 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10628 pub temperature: i16,
10629}
10630impl RAW_IMU_DATA {
10631 pub const ENCODED_LEN: usize = 29usize;
10632 pub const DEFAULT: Self = Self {
10633 time_usec: 0_u64,
10634 xacc: 0_i16,
10635 yacc: 0_i16,
10636 zacc: 0_i16,
10637 xgyro: 0_i16,
10638 ygyro: 0_i16,
10639 zgyro: 0_i16,
10640 xmag: 0_i16,
10641 ymag: 0_i16,
10642 zmag: 0_i16,
10643 id: 0_u8,
10644 temperature: 0_i16,
10645 };
10646 #[cfg(feature = "arbitrary")]
10647 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10648 use arbitrary::{Arbitrary, Unstructured};
10649 let mut buf = [0u8; 1024];
10650 rng.fill_bytes(&mut buf);
10651 let mut unstructured = Unstructured::new(&buf);
10652 Self::arbitrary(&mut unstructured).unwrap_or_default()
10653 }
10654}
10655impl Default for RAW_IMU_DATA {
10656 fn default() -> Self {
10657 Self::DEFAULT.clone()
10658 }
10659}
10660impl MessageData for RAW_IMU_DATA {
10661 type Message = MavMessage;
10662 const ID: u32 = 27u32;
10663 const NAME: &'static str = "RAW_IMU";
10664 const EXTRA_CRC: u8 = 144u8;
10665 const ENCODED_LEN: usize = 29usize;
10666 fn deser(
10667 _version: MavlinkVersion,
10668 __input: &[u8],
10669 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10670 let avail_len = __input.len();
10671 let mut payload_buf = [0; Self::ENCODED_LEN];
10672 let mut buf = if avail_len < Self::ENCODED_LEN {
10673 payload_buf[0..avail_len].copy_from_slice(__input);
10674 Bytes::new(&payload_buf)
10675 } else {
10676 Bytes::new(__input)
10677 };
10678 let mut __struct = Self::default();
10679 __struct.time_usec = buf.get_u64_le();
10680 __struct.xacc = buf.get_i16_le();
10681 __struct.yacc = buf.get_i16_le();
10682 __struct.zacc = buf.get_i16_le();
10683 __struct.xgyro = buf.get_i16_le();
10684 __struct.ygyro = buf.get_i16_le();
10685 __struct.zgyro = buf.get_i16_le();
10686 __struct.xmag = buf.get_i16_le();
10687 __struct.ymag = buf.get_i16_le();
10688 __struct.zmag = buf.get_i16_le();
10689 __struct.id = buf.get_u8();
10690 __struct.temperature = buf.get_i16_le();
10691 Ok(__struct)
10692 }
10693 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10694 let mut __tmp = BytesMut::new(bytes);
10695 #[allow(clippy::absurd_extreme_comparisons)]
10696 #[allow(unused_comparisons)]
10697 if __tmp.remaining() < Self::ENCODED_LEN {
10698 panic!(
10699 "buffer is too small (need {} bytes, but got {})",
10700 Self::ENCODED_LEN,
10701 __tmp.remaining(),
10702 )
10703 }
10704 __tmp.put_u64_le(self.time_usec);
10705 __tmp.put_i16_le(self.xacc);
10706 __tmp.put_i16_le(self.yacc);
10707 __tmp.put_i16_le(self.zacc);
10708 __tmp.put_i16_le(self.xgyro);
10709 __tmp.put_i16_le(self.ygyro);
10710 __tmp.put_i16_le(self.zgyro);
10711 __tmp.put_i16_le(self.xmag);
10712 __tmp.put_i16_le(self.ymag);
10713 __tmp.put_i16_le(self.zmag);
10714 __tmp.put_u8(self.id);
10715 __tmp.put_i16_le(self.temperature);
10716 if matches!(version, MavlinkVersion::V2) {
10717 let len = __tmp.len();
10718 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10719 } else {
10720 __tmp.len()
10721 }
10722 }
10723}
10724#[doc = "id: 234"]
10725#[doc = "Message appropriate for high latency connections like Iridium."]
10726#[derive(Debug, Clone, PartialEq)]
10727#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10728#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10729pub struct HIGH_LATENCY_DATA {
10730 #[doc = "A bitfield for use for autopilot-specific flags."]
10731 pub custom_mode: u32,
10732 #[doc = "Latitude"]
10733 pub latitude: i32,
10734 #[doc = "Longitude"]
10735 pub longitude: i32,
10736 #[doc = "roll"]
10737 pub roll: i16,
10738 #[doc = "pitch"]
10739 pub pitch: i16,
10740 #[doc = "heading"]
10741 pub heading: u16,
10742 #[doc = "heading setpoint"]
10743 pub heading_sp: i16,
10744 #[doc = "Altitude above mean sea level"]
10745 pub altitude_amsl: i16,
10746 #[doc = "Altitude setpoint relative to the home position"]
10747 pub altitude_sp: i16,
10748 #[doc = "distance to target"]
10749 pub wp_distance: u16,
10750 #[doc = "Bitmap of enabled system modes."]
10751 pub base_mode: MavModeFlag,
10752 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
10753 pub landed_state: MavLandedState,
10754 #[doc = "throttle (percentage)"]
10755 pub throttle: i8,
10756 #[doc = "airspeed"]
10757 pub airspeed: u8,
10758 #[doc = "airspeed setpoint"]
10759 pub airspeed_sp: u8,
10760 #[doc = "groundspeed"]
10761 pub groundspeed: u8,
10762 #[doc = "climb rate"]
10763 pub climb_rate: i8,
10764 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
10765 pub gps_nsat: u8,
10766 #[doc = "GPS Fix type."]
10767 pub gps_fix_type: GpsFixType,
10768 #[doc = "Remaining battery (percentage)"]
10769 pub battery_remaining: u8,
10770 #[doc = "Autopilot temperature (degrees C)"]
10771 pub temperature: i8,
10772 #[doc = "Air temperature (degrees C) from airspeed sensor"]
10773 pub temperature_air: i8,
10774 #[doc = "failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)"]
10775 pub failsafe: u8,
10776 #[doc = "current waypoint number"]
10777 pub wp_num: u8,
10778}
10779impl HIGH_LATENCY_DATA {
10780 pub const ENCODED_LEN: usize = 40usize;
10781 pub const DEFAULT: Self = Self {
10782 custom_mode: 0_u32,
10783 latitude: 0_i32,
10784 longitude: 0_i32,
10785 roll: 0_i16,
10786 pitch: 0_i16,
10787 heading: 0_u16,
10788 heading_sp: 0_i16,
10789 altitude_amsl: 0_i16,
10790 altitude_sp: 0_i16,
10791 wp_distance: 0_u16,
10792 base_mode: MavModeFlag::DEFAULT,
10793 landed_state: MavLandedState::DEFAULT,
10794 throttle: 0_i8,
10795 airspeed: 0_u8,
10796 airspeed_sp: 0_u8,
10797 groundspeed: 0_u8,
10798 climb_rate: 0_i8,
10799 gps_nsat: 0_u8,
10800 gps_fix_type: GpsFixType::DEFAULT,
10801 battery_remaining: 0_u8,
10802 temperature: 0_i8,
10803 temperature_air: 0_i8,
10804 failsafe: 0_u8,
10805 wp_num: 0_u8,
10806 };
10807 #[cfg(feature = "arbitrary")]
10808 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10809 use arbitrary::{Arbitrary, Unstructured};
10810 let mut buf = [0u8; 1024];
10811 rng.fill_bytes(&mut buf);
10812 let mut unstructured = Unstructured::new(&buf);
10813 Self::arbitrary(&mut unstructured).unwrap_or_default()
10814 }
10815}
10816impl Default for HIGH_LATENCY_DATA {
10817 fn default() -> Self {
10818 Self::DEFAULT.clone()
10819 }
10820}
10821impl MessageData for HIGH_LATENCY_DATA {
10822 type Message = MavMessage;
10823 const ID: u32 = 234u32;
10824 const NAME: &'static str = "HIGH_LATENCY";
10825 const EXTRA_CRC: u8 = 150u8;
10826 const ENCODED_LEN: usize = 40usize;
10827 fn deser(
10828 _version: MavlinkVersion,
10829 __input: &[u8],
10830 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10831 let avail_len = __input.len();
10832 let mut payload_buf = [0; Self::ENCODED_LEN];
10833 let mut buf = if avail_len < Self::ENCODED_LEN {
10834 payload_buf[0..avail_len].copy_from_slice(__input);
10835 Bytes::new(&payload_buf)
10836 } else {
10837 Bytes::new(__input)
10838 };
10839 let mut __struct = Self::default();
10840 __struct.custom_mode = buf.get_u32_le();
10841 __struct.latitude = buf.get_i32_le();
10842 __struct.longitude = buf.get_i32_le();
10843 __struct.roll = buf.get_i16_le();
10844 __struct.pitch = buf.get_i16_le();
10845 __struct.heading = buf.get_u16_le();
10846 __struct.heading_sp = buf.get_i16_le();
10847 __struct.altitude_amsl = buf.get_i16_le();
10848 __struct.altitude_sp = buf.get_i16_le();
10849 __struct.wp_distance = buf.get_u16_le();
10850 let tmp = buf.get_u8();
10851 __struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
10852 ::mavlink_core::error::ParserError::InvalidFlag {
10853 flag_type: "MavModeFlag",
10854 value: tmp as u32,
10855 },
10856 )?;
10857 let tmp = buf.get_u8();
10858 __struct.landed_state =
10859 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10860 enum_type: "MavLandedState",
10861 value: tmp as u32,
10862 })?;
10863 __struct.throttle = buf.get_i8();
10864 __struct.airspeed = buf.get_u8();
10865 __struct.airspeed_sp = buf.get_u8();
10866 __struct.groundspeed = buf.get_u8();
10867 __struct.climb_rate = buf.get_i8();
10868 __struct.gps_nsat = buf.get_u8();
10869 let tmp = buf.get_u8();
10870 __struct.gps_fix_type =
10871 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10872 enum_type: "GpsFixType",
10873 value: tmp as u32,
10874 })?;
10875 __struct.battery_remaining = buf.get_u8();
10876 __struct.temperature = buf.get_i8();
10877 __struct.temperature_air = buf.get_i8();
10878 __struct.failsafe = buf.get_u8();
10879 __struct.wp_num = buf.get_u8();
10880 Ok(__struct)
10881 }
10882 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10883 let mut __tmp = BytesMut::new(bytes);
10884 #[allow(clippy::absurd_extreme_comparisons)]
10885 #[allow(unused_comparisons)]
10886 if __tmp.remaining() < Self::ENCODED_LEN {
10887 panic!(
10888 "buffer is too small (need {} bytes, but got {})",
10889 Self::ENCODED_LEN,
10890 __tmp.remaining(),
10891 )
10892 }
10893 __tmp.put_u32_le(self.custom_mode);
10894 __tmp.put_i32_le(self.latitude);
10895 __tmp.put_i32_le(self.longitude);
10896 __tmp.put_i16_le(self.roll);
10897 __tmp.put_i16_le(self.pitch);
10898 __tmp.put_u16_le(self.heading);
10899 __tmp.put_i16_le(self.heading_sp);
10900 __tmp.put_i16_le(self.altitude_amsl);
10901 __tmp.put_i16_le(self.altitude_sp);
10902 __tmp.put_u16_le(self.wp_distance);
10903 __tmp.put_u8(self.base_mode.bits());
10904 __tmp.put_u8(self.landed_state as u8);
10905 __tmp.put_i8(self.throttle);
10906 __tmp.put_u8(self.airspeed);
10907 __tmp.put_u8(self.airspeed_sp);
10908 __tmp.put_u8(self.groundspeed);
10909 __tmp.put_i8(self.climb_rate);
10910 __tmp.put_u8(self.gps_nsat);
10911 __tmp.put_u8(self.gps_fix_type as u8);
10912 __tmp.put_u8(self.battery_remaining);
10913 __tmp.put_i8(self.temperature);
10914 __tmp.put_i8(self.temperature_air);
10915 __tmp.put_u8(self.failsafe);
10916 __tmp.put_u8(self.wp_num);
10917 if matches!(version, MavlinkVersion::V2) {
10918 let len = __tmp.len();
10919 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10920 } else {
10921 __tmp.len()
10922 }
10923 }
10924}
10925#[doc = "id: 437"]
10926#[doc = "A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. A receiver must re-request all available modes whenever the sequence number changes. This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. See <https://mavlink.io/en/services/standard_modes.html>."]
10927#[derive(Debug, Clone, PartialEq)]
10928#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10929#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10930pub struct AVAILABLE_MODES_MONITOR_DATA {
10931 #[doc = "Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically)."]
10932 pub seq: u8,
10933}
10934impl AVAILABLE_MODES_MONITOR_DATA {
10935 pub const ENCODED_LEN: usize = 1usize;
10936 pub const DEFAULT: Self = Self { seq: 0_u8 };
10937 #[cfg(feature = "arbitrary")]
10938 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10939 use arbitrary::{Arbitrary, Unstructured};
10940 let mut buf = [0u8; 1024];
10941 rng.fill_bytes(&mut buf);
10942 let mut unstructured = Unstructured::new(&buf);
10943 Self::arbitrary(&mut unstructured).unwrap_or_default()
10944 }
10945}
10946impl Default for AVAILABLE_MODES_MONITOR_DATA {
10947 fn default() -> Self {
10948 Self::DEFAULT.clone()
10949 }
10950}
10951impl MessageData for AVAILABLE_MODES_MONITOR_DATA {
10952 type Message = MavMessage;
10953 const ID: u32 = 437u32;
10954 const NAME: &'static str = "AVAILABLE_MODES_MONITOR";
10955 const EXTRA_CRC: u8 = 30u8;
10956 const ENCODED_LEN: usize = 1usize;
10957 fn deser(
10958 _version: MavlinkVersion,
10959 __input: &[u8],
10960 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10961 let avail_len = __input.len();
10962 let mut payload_buf = [0; Self::ENCODED_LEN];
10963 let mut buf = if avail_len < Self::ENCODED_LEN {
10964 payload_buf[0..avail_len].copy_from_slice(__input);
10965 Bytes::new(&payload_buf)
10966 } else {
10967 Bytes::new(__input)
10968 };
10969 let mut __struct = Self::default();
10970 __struct.seq = buf.get_u8();
10971 Ok(__struct)
10972 }
10973 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10974 let mut __tmp = BytesMut::new(bytes);
10975 #[allow(clippy::absurd_extreme_comparisons)]
10976 #[allow(unused_comparisons)]
10977 if __tmp.remaining() < Self::ENCODED_LEN {
10978 panic!(
10979 "buffer is too small (need {} bytes, but got {})",
10980 Self::ENCODED_LEN,
10981 __tmp.remaining(),
10982 )
10983 }
10984 __tmp.put_u8(self.seq);
10985 if matches!(version, MavlinkVersion::V2) {
10986 let len = __tmp.len();
10987 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10988 } else {
10989 __tmp.len()
10990 }
10991 }
10992}
10993#[doc = "id: 440"]
10994#[doc = "Illuminator status."]
10995#[derive(Debug, Clone, PartialEq)]
10996#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10997#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10998pub struct ILLUMINATOR_STATUS_DATA {
10999 #[doc = "Time since the start-up of the illuminator in ms"]
11000 pub uptime_ms: u32,
11001 #[doc = "Errors"]
11002 pub error_status: IlluminatorErrorFlags,
11003 #[doc = "Illuminator brightness"]
11004 pub brightness: f32,
11005 #[doc = "Illuminator strobing period in seconds"]
11006 pub strobe_period: f32,
11007 #[doc = "Illuminator strobing duty cycle"]
11008 pub strobe_duty_cycle: f32,
11009 #[doc = "Temperature in Celsius"]
11010 pub temp_c: f32,
11011 #[doc = "Minimum strobing period in seconds"]
11012 pub min_strobe_period: f32,
11013 #[doc = "Maximum strobing period in seconds"]
11014 pub max_strobe_period: f32,
11015 #[doc = "0: Illuminators OFF, 1: Illuminators ON"]
11016 pub enable: u8,
11017 #[doc = "Supported illuminator modes"]
11018 pub mode_bitmask: IlluminatorMode,
11019 #[doc = "Illuminator mode"]
11020 pub mode: IlluminatorMode,
11021}
11022impl ILLUMINATOR_STATUS_DATA {
11023 pub const ENCODED_LEN: usize = 35usize;
11024 pub const DEFAULT: Self = Self {
11025 uptime_ms: 0_u32,
11026 error_status: IlluminatorErrorFlags::DEFAULT,
11027 brightness: 0.0_f32,
11028 strobe_period: 0.0_f32,
11029 strobe_duty_cycle: 0.0_f32,
11030 temp_c: 0.0_f32,
11031 min_strobe_period: 0.0_f32,
11032 max_strobe_period: 0.0_f32,
11033 enable: 0_u8,
11034 mode_bitmask: IlluminatorMode::DEFAULT,
11035 mode: IlluminatorMode::DEFAULT,
11036 };
11037 #[cfg(feature = "arbitrary")]
11038 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11039 use arbitrary::{Arbitrary, Unstructured};
11040 let mut buf = [0u8; 1024];
11041 rng.fill_bytes(&mut buf);
11042 let mut unstructured = Unstructured::new(&buf);
11043 Self::arbitrary(&mut unstructured).unwrap_or_default()
11044 }
11045}
11046impl Default for ILLUMINATOR_STATUS_DATA {
11047 fn default() -> Self {
11048 Self::DEFAULT.clone()
11049 }
11050}
11051impl MessageData for ILLUMINATOR_STATUS_DATA {
11052 type Message = MavMessage;
11053 const ID: u32 = 440u32;
11054 const NAME: &'static str = "ILLUMINATOR_STATUS";
11055 const EXTRA_CRC: u8 = 66u8;
11056 const ENCODED_LEN: usize = 35usize;
11057 fn deser(
11058 _version: MavlinkVersion,
11059 __input: &[u8],
11060 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11061 let avail_len = __input.len();
11062 let mut payload_buf = [0; Self::ENCODED_LEN];
11063 let mut buf = if avail_len < Self::ENCODED_LEN {
11064 payload_buf[0..avail_len].copy_from_slice(__input);
11065 Bytes::new(&payload_buf)
11066 } else {
11067 Bytes::new(__input)
11068 };
11069 let mut __struct = Self::default();
11070 __struct.uptime_ms = buf.get_u32_le();
11071 let tmp = buf.get_u32_le();
11072 __struct.error_status = IlluminatorErrorFlags::from_bits(
11073 tmp & IlluminatorErrorFlags::all().bits(),
11074 )
11075 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
11076 flag_type: "IlluminatorErrorFlags",
11077 value: tmp as u32,
11078 })?;
11079 __struct.brightness = buf.get_f32_le();
11080 __struct.strobe_period = buf.get_f32_le();
11081 __struct.strobe_duty_cycle = buf.get_f32_le();
11082 __struct.temp_c = buf.get_f32_le();
11083 __struct.min_strobe_period = buf.get_f32_le();
11084 __struct.max_strobe_period = buf.get_f32_le();
11085 __struct.enable = buf.get_u8();
11086 let tmp = buf.get_u8();
11087 __struct.mode_bitmask =
11088 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11089 enum_type: "IlluminatorMode",
11090 value: tmp as u32,
11091 })?;
11092 let tmp = buf.get_u8();
11093 __struct.mode =
11094 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11095 enum_type: "IlluminatorMode",
11096 value: tmp as u32,
11097 })?;
11098 Ok(__struct)
11099 }
11100 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11101 let mut __tmp = BytesMut::new(bytes);
11102 #[allow(clippy::absurd_extreme_comparisons)]
11103 #[allow(unused_comparisons)]
11104 if __tmp.remaining() < Self::ENCODED_LEN {
11105 panic!(
11106 "buffer is too small (need {} bytes, but got {})",
11107 Self::ENCODED_LEN,
11108 __tmp.remaining(),
11109 )
11110 }
11111 __tmp.put_u32_le(self.uptime_ms);
11112 __tmp.put_u32_le(self.error_status.bits());
11113 __tmp.put_f32_le(self.brightness);
11114 __tmp.put_f32_le(self.strobe_period);
11115 __tmp.put_f32_le(self.strobe_duty_cycle);
11116 __tmp.put_f32_le(self.temp_c);
11117 __tmp.put_f32_le(self.min_strobe_period);
11118 __tmp.put_f32_le(self.max_strobe_period);
11119 __tmp.put_u8(self.enable);
11120 __tmp.put_u8(self.mode_bitmask as u8);
11121 __tmp.put_u8(self.mode as u8);
11122 if matches!(version, MavlinkVersion::V2) {
11123 let len = __tmp.len();
11124 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11125 } else {
11126 __tmp.len()
11127 }
11128 }
11129}
11130#[doc = "id: 73"]
11131#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
11132#[derive(Debug, Clone, PartialEq)]
11133#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11134#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11135pub struct MISSION_ITEM_INT_DATA {
11136 #[doc = "PARAM1, see MAV_CMD enum"]
11137 pub param1: f32,
11138 #[doc = "PARAM2, see MAV_CMD enum"]
11139 pub param2: f32,
11140 #[doc = "PARAM3, see MAV_CMD enum"]
11141 pub param3: f32,
11142 #[doc = "PARAM4, see MAV_CMD enum"]
11143 pub param4: f32,
11144 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
11145 pub x: i32,
11146 #[doc = "PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7"]
11147 pub y: i32,
11148 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame."]
11149 pub z: f32,
11150 #[doc = "Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4)."]
11151 pub seq: u16,
11152 #[doc = "The scheduled action for the waypoint."]
11153 pub command: MavCmd,
11154 #[doc = "System ID"]
11155 pub target_system: u8,
11156 #[doc = "Component ID"]
11157 pub target_component: u8,
11158 #[doc = "The coordinate system of the waypoint."]
11159 pub frame: MavFrame,
11160 #[doc = "false:0, true:1"]
11161 pub current: u8,
11162 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
11163 pub autocontinue: u8,
11164 #[doc = "Mission type."]
11165 #[cfg_attr(feature = "serde", serde(default))]
11166 pub mission_type: MavMissionType,
11167}
11168impl MISSION_ITEM_INT_DATA {
11169 pub const ENCODED_LEN: usize = 38usize;
11170 pub const DEFAULT: Self = Self {
11171 param1: 0.0_f32,
11172 param2: 0.0_f32,
11173 param3: 0.0_f32,
11174 param4: 0.0_f32,
11175 x: 0_i32,
11176 y: 0_i32,
11177 z: 0.0_f32,
11178 seq: 0_u16,
11179 command: MavCmd::DEFAULT,
11180 target_system: 0_u8,
11181 target_component: 0_u8,
11182 frame: MavFrame::DEFAULT,
11183 current: 0_u8,
11184 autocontinue: 0_u8,
11185 mission_type: MavMissionType::DEFAULT,
11186 };
11187 #[cfg(feature = "arbitrary")]
11188 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11189 use arbitrary::{Arbitrary, Unstructured};
11190 let mut buf = [0u8; 1024];
11191 rng.fill_bytes(&mut buf);
11192 let mut unstructured = Unstructured::new(&buf);
11193 Self::arbitrary(&mut unstructured).unwrap_or_default()
11194 }
11195}
11196impl Default for MISSION_ITEM_INT_DATA {
11197 fn default() -> Self {
11198 Self::DEFAULT.clone()
11199 }
11200}
11201impl MessageData for MISSION_ITEM_INT_DATA {
11202 type Message = MavMessage;
11203 const ID: u32 = 73u32;
11204 const NAME: &'static str = "MISSION_ITEM_INT";
11205 const EXTRA_CRC: u8 = 38u8;
11206 const ENCODED_LEN: usize = 38usize;
11207 fn deser(
11208 _version: MavlinkVersion,
11209 __input: &[u8],
11210 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11211 let avail_len = __input.len();
11212 let mut payload_buf = [0; Self::ENCODED_LEN];
11213 let mut buf = if avail_len < Self::ENCODED_LEN {
11214 payload_buf[0..avail_len].copy_from_slice(__input);
11215 Bytes::new(&payload_buf)
11216 } else {
11217 Bytes::new(__input)
11218 };
11219 let mut __struct = Self::default();
11220 __struct.param1 = buf.get_f32_le();
11221 __struct.param2 = buf.get_f32_le();
11222 __struct.param3 = buf.get_f32_le();
11223 __struct.param4 = buf.get_f32_le();
11224 __struct.x = buf.get_i32_le();
11225 __struct.y = buf.get_i32_le();
11226 __struct.z = buf.get_f32_le();
11227 __struct.seq = buf.get_u16_le();
11228 let tmp = buf.get_u16_le();
11229 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
11230 ::mavlink_core::error::ParserError::InvalidEnum {
11231 enum_type: "MavCmd",
11232 value: tmp as u32,
11233 },
11234 )?;
11235 __struct.target_system = buf.get_u8();
11236 __struct.target_component = buf.get_u8();
11237 let tmp = buf.get_u8();
11238 __struct.frame =
11239 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11240 enum_type: "MavFrame",
11241 value: tmp as u32,
11242 })?;
11243 __struct.current = buf.get_u8();
11244 __struct.autocontinue = buf.get_u8();
11245 let tmp = buf.get_u8();
11246 __struct.mission_type =
11247 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11248 enum_type: "MavMissionType",
11249 value: tmp as u32,
11250 })?;
11251 Ok(__struct)
11252 }
11253 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11254 let mut __tmp = BytesMut::new(bytes);
11255 #[allow(clippy::absurd_extreme_comparisons)]
11256 #[allow(unused_comparisons)]
11257 if __tmp.remaining() < Self::ENCODED_LEN {
11258 panic!(
11259 "buffer is too small (need {} bytes, but got {})",
11260 Self::ENCODED_LEN,
11261 __tmp.remaining(),
11262 )
11263 }
11264 __tmp.put_f32_le(self.param1);
11265 __tmp.put_f32_le(self.param2);
11266 __tmp.put_f32_le(self.param3);
11267 __tmp.put_f32_le(self.param4);
11268 __tmp.put_i32_le(self.x);
11269 __tmp.put_i32_le(self.y);
11270 __tmp.put_f32_le(self.z);
11271 __tmp.put_u16_le(self.seq);
11272 __tmp.put_u16_le(self.command as u16);
11273 __tmp.put_u8(self.target_system);
11274 __tmp.put_u8(self.target_component);
11275 __tmp.put_u8(self.frame as u8);
11276 __tmp.put_u8(self.current);
11277 __tmp.put_u8(self.autocontinue);
11278 __tmp.put_u8(self.mission_type as u8);
11279 if matches!(version, MavlinkVersion::V2) {
11280 let len = __tmp.len();
11281 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11282 } else {
11283 __tmp.len()
11284 }
11285 }
11286}
11287#[doc = "id: 436"]
11288#[doc = "Get the current mode. This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). It may be requested using MAV_CMD_REQUEST_MESSAGE. See <https://mavlink.io/en/services/standard_modes.html>."]
11289#[derive(Debug, Clone, PartialEq)]
11290#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11291#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11292pub struct CURRENT_MODE_DATA {
11293 #[doc = "A bitfield for use for autopilot-specific flags"]
11294 pub custom_mode: u32,
11295 #[doc = "The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied"]
11296 pub intended_custom_mode: u32,
11297 #[doc = "Standard mode."]
11298 pub standard_mode: MavStandardMode,
11299}
11300impl CURRENT_MODE_DATA {
11301 pub const ENCODED_LEN: usize = 9usize;
11302 pub const DEFAULT: Self = Self {
11303 custom_mode: 0_u32,
11304 intended_custom_mode: 0_u32,
11305 standard_mode: MavStandardMode::DEFAULT,
11306 };
11307 #[cfg(feature = "arbitrary")]
11308 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11309 use arbitrary::{Arbitrary, Unstructured};
11310 let mut buf = [0u8; 1024];
11311 rng.fill_bytes(&mut buf);
11312 let mut unstructured = Unstructured::new(&buf);
11313 Self::arbitrary(&mut unstructured).unwrap_or_default()
11314 }
11315}
11316impl Default for CURRENT_MODE_DATA {
11317 fn default() -> Self {
11318 Self::DEFAULT.clone()
11319 }
11320}
11321impl MessageData for CURRENT_MODE_DATA {
11322 type Message = MavMessage;
11323 const ID: u32 = 436u32;
11324 const NAME: &'static str = "CURRENT_MODE";
11325 const EXTRA_CRC: u8 = 193u8;
11326 const ENCODED_LEN: usize = 9usize;
11327 fn deser(
11328 _version: MavlinkVersion,
11329 __input: &[u8],
11330 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11331 let avail_len = __input.len();
11332 let mut payload_buf = [0; Self::ENCODED_LEN];
11333 let mut buf = if avail_len < Self::ENCODED_LEN {
11334 payload_buf[0..avail_len].copy_from_slice(__input);
11335 Bytes::new(&payload_buf)
11336 } else {
11337 Bytes::new(__input)
11338 };
11339 let mut __struct = Self::default();
11340 __struct.custom_mode = buf.get_u32_le();
11341 __struct.intended_custom_mode = buf.get_u32_le();
11342 let tmp = buf.get_u8();
11343 __struct.standard_mode =
11344 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11345 enum_type: "MavStandardMode",
11346 value: tmp as u32,
11347 })?;
11348 Ok(__struct)
11349 }
11350 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11351 let mut __tmp = BytesMut::new(bytes);
11352 #[allow(clippy::absurd_extreme_comparisons)]
11353 #[allow(unused_comparisons)]
11354 if __tmp.remaining() < Self::ENCODED_LEN {
11355 panic!(
11356 "buffer is too small (need {} bytes, but got {})",
11357 Self::ENCODED_LEN,
11358 __tmp.remaining(),
11359 )
11360 }
11361 __tmp.put_u32_le(self.custom_mode);
11362 __tmp.put_u32_le(self.intended_custom_mode);
11363 __tmp.put_u8(self.standard_mode as u8);
11364 if matches!(version, MavlinkVersion::V2) {
11365 let len = __tmp.len();
11366 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11367 } else {
11368 __tmp.len()
11369 }
11370 }
11371}
11372#[doc = "id: 26"]
11373#[doc = "The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units."]
11374#[derive(Debug, Clone, PartialEq)]
11375#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11376#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11377pub struct SCALED_IMU_DATA {
11378 #[doc = "Timestamp (time since system boot)."]
11379 pub time_boot_ms: u32,
11380 #[doc = "X acceleration"]
11381 pub xacc: i16,
11382 #[doc = "Y acceleration"]
11383 pub yacc: i16,
11384 #[doc = "Z acceleration"]
11385 pub zacc: i16,
11386 #[doc = "Angular speed around X axis"]
11387 pub xgyro: i16,
11388 #[doc = "Angular speed around Y axis"]
11389 pub ygyro: i16,
11390 #[doc = "Angular speed around Z axis"]
11391 pub zgyro: i16,
11392 #[doc = "X Magnetic field"]
11393 pub xmag: i16,
11394 #[doc = "Y Magnetic field"]
11395 pub ymag: i16,
11396 #[doc = "Z Magnetic field"]
11397 pub zmag: i16,
11398 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
11399 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
11400 pub temperature: i16,
11401}
11402impl SCALED_IMU_DATA {
11403 pub const ENCODED_LEN: usize = 24usize;
11404 pub const DEFAULT: Self = Self {
11405 time_boot_ms: 0_u32,
11406 xacc: 0_i16,
11407 yacc: 0_i16,
11408 zacc: 0_i16,
11409 xgyro: 0_i16,
11410 ygyro: 0_i16,
11411 zgyro: 0_i16,
11412 xmag: 0_i16,
11413 ymag: 0_i16,
11414 zmag: 0_i16,
11415 temperature: 0_i16,
11416 };
11417 #[cfg(feature = "arbitrary")]
11418 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11419 use arbitrary::{Arbitrary, Unstructured};
11420 let mut buf = [0u8; 1024];
11421 rng.fill_bytes(&mut buf);
11422 let mut unstructured = Unstructured::new(&buf);
11423 Self::arbitrary(&mut unstructured).unwrap_or_default()
11424 }
11425}
11426impl Default for SCALED_IMU_DATA {
11427 fn default() -> Self {
11428 Self::DEFAULT.clone()
11429 }
11430}
11431impl MessageData for SCALED_IMU_DATA {
11432 type Message = MavMessage;
11433 const ID: u32 = 26u32;
11434 const NAME: &'static str = "SCALED_IMU";
11435 const EXTRA_CRC: u8 = 170u8;
11436 const ENCODED_LEN: usize = 24usize;
11437 fn deser(
11438 _version: MavlinkVersion,
11439 __input: &[u8],
11440 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11441 let avail_len = __input.len();
11442 let mut payload_buf = [0; Self::ENCODED_LEN];
11443 let mut buf = if avail_len < Self::ENCODED_LEN {
11444 payload_buf[0..avail_len].copy_from_slice(__input);
11445 Bytes::new(&payload_buf)
11446 } else {
11447 Bytes::new(__input)
11448 };
11449 let mut __struct = Self::default();
11450 __struct.time_boot_ms = buf.get_u32_le();
11451 __struct.xacc = buf.get_i16_le();
11452 __struct.yacc = buf.get_i16_le();
11453 __struct.zacc = buf.get_i16_le();
11454 __struct.xgyro = buf.get_i16_le();
11455 __struct.ygyro = buf.get_i16_le();
11456 __struct.zgyro = buf.get_i16_le();
11457 __struct.xmag = buf.get_i16_le();
11458 __struct.ymag = buf.get_i16_le();
11459 __struct.zmag = buf.get_i16_le();
11460 __struct.temperature = buf.get_i16_le();
11461 Ok(__struct)
11462 }
11463 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11464 let mut __tmp = BytesMut::new(bytes);
11465 #[allow(clippy::absurd_extreme_comparisons)]
11466 #[allow(unused_comparisons)]
11467 if __tmp.remaining() < Self::ENCODED_LEN {
11468 panic!(
11469 "buffer is too small (need {} bytes, but got {})",
11470 Self::ENCODED_LEN,
11471 __tmp.remaining(),
11472 )
11473 }
11474 __tmp.put_u32_le(self.time_boot_ms);
11475 __tmp.put_i16_le(self.xacc);
11476 __tmp.put_i16_le(self.yacc);
11477 __tmp.put_i16_le(self.zacc);
11478 __tmp.put_i16_le(self.xgyro);
11479 __tmp.put_i16_le(self.ygyro);
11480 __tmp.put_i16_le(self.zgyro);
11481 __tmp.put_i16_le(self.xmag);
11482 __tmp.put_i16_le(self.ymag);
11483 __tmp.put_i16_le(self.zmag);
11484 __tmp.put_i16_le(self.temperature);
11485 if matches!(version, MavlinkVersion::V2) {
11486 let len = __tmp.len();
11487 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11488 } else {
11489 __tmp.len()
11490 }
11491 }
11492}
11493#[doc = "id: 55"]
11494#[doc = "Read out the safety zone the MAV currently assumes."]
11495#[derive(Debug, Clone, PartialEq)]
11496#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11497#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11498pub struct SAFETY_ALLOWED_AREA_DATA {
11499 #[doc = "x position 1 / Latitude 1"]
11500 pub p1x: f32,
11501 #[doc = "y position 1 / Longitude 1"]
11502 pub p1y: f32,
11503 #[doc = "z position 1 / Altitude 1"]
11504 pub p1z: f32,
11505 #[doc = "x position 2 / Latitude 2"]
11506 pub p2x: f32,
11507 #[doc = "y position 2 / Longitude 2"]
11508 pub p2y: f32,
11509 #[doc = "z position 2 / Altitude 2"]
11510 pub p2z: f32,
11511 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
11512 pub frame: MavFrame,
11513}
11514impl SAFETY_ALLOWED_AREA_DATA {
11515 pub const ENCODED_LEN: usize = 25usize;
11516 pub const DEFAULT: Self = Self {
11517 p1x: 0.0_f32,
11518 p1y: 0.0_f32,
11519 p1z: 0.0_f32,
11520 p2x: 0.0_f32,
11521 p2y: 0.0_f32,
11522 p2z: 0.0_f32,
11523 frame: MavFrame::DEFAULT,
11524 };
11525 #[cfg(feature = "arbitrary")]
11526 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11527 use arbitrary::{Arbitrary, Unstructured};
11528 let mut buf = [0u8; 1024];
11529 rng.fill_bytes(&mut buf);
11530 let mut unstructured = Unstructured::new(&buf);
11531 Self::arbitrary(&mut unstructured).unwrap_or_default()
11532 }
11533}
11534impl Default for SAFETY_ALLOWED_AREA_DATA {
11535 fn default() -> Self {
11536 Self::DEFAULT.clone()
11537 }
11538}
11539impl MessageData for SAFETY_ALLOWED_AREA_DATA {
11540 type Message = MavMessage;
11541 const ID: u32 = 55u32;
11542 const NAME: &'static str = "SAFETY_ALLOWED_AREA";
11543 const EXTRA_CRC: u8 = 3u8;
11544 const ENCODED_LEN: usize = 25usize;
11545 fn deser(
11546 _version: MavlinkVersion,
11547 __input: &[u8],
11548 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11549 let avail_len = __input.len();
11550 let mut payload_buf = [0; Self::ENCODED_LEN];
11551 let mut buf = if avail_len < Self::ENCODED_LEN {
11552 payload_buf[0..avail_len].copy_from_slice(__input);
11553 Bytes::new(&payload_buf)
11554 } else {
11555 Bytes::new(__input)
11556 };
11557 let mut __struct = Self::default();
11558 __struct.p1x = buf.get_f32_le();
11559 __struct.p1y = buf.get_f32_le();
11560 __struct.p1z = buf.get_f32_le();
11561 __struct.p2x = buf.get_f32_le();
11562 __struct.p2y = buf.get_f32_le();
11563 __struct.p2z = buf.get_f32_le();
11564 let tmp = buf.get_u8();
11565 __struct.frame =
11566 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11567 enum_type: "MavFrame",
11568 value: tmp as u32,
11569 })?;
11570 Ok(__struct)
11571 }
11572 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11573 let mut __tmp = BytesMut::new(bytes);
11574 #[allow(clippy::absurd_extreme_comparisons)]
11575 #[allow(unused_comparisons)]
11576 if __tmp.remaining() < Self::ENCODED_LEN {
11577 panic!(
11578 "buffer is too small (need {} bytes, but got {})",
11579 Self::ENCODED_LEN,
11580 __tmp.remaining(),
11581 )
11582 }
11583 __tmp.put_f32_le(self.p1x);
11584 __tmp.put_f32_le(self.p1y);
11585 __tmp.put_f32_le(self.p1z);
11586 __tmp.put_f32_le(self.p2x);
11587 __tmp.put_f32_le(self.p2y);
11588 __tmp.put_f32_le(self.p2z);
11589 __tmp.put_u8(self.frame as u8);
11590 if matches!(version, MavlinkVersion::V2) {
11591 let len = __tmp.len();
11592 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11593 } else {
11594 __tmp.len()
11595 }
11596 }
11597}
11598#[doc = "id: 135"]
11599#[doc = "Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission."]
11600#[derive(Debug, Clone, PartialEq)]
11601#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11602#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11603pub struct TERRAIN_CHECK_DATA {
11604 #[doc = "Latitude"]
11605 pub lat: i32,
11606 #[doc = "Longitude"]
11607 pub lon: i32,
11608}
11609impl TERRAIN_CHECK_DATA {
11610 pub const ENCODED_LEN: usize = 8usize;
11611 pub const DEFAULT: Self = Self {
11612 lat: 0_i32,
11613 lon: 0_i32,
11614 };
11615 #[cfg(feature = "arbitrary")]
11616 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11617 use arbitrary::{Arbitrary, Unstructured};
11618 let mut buf = [0u8; 1024];
11619 rng.fill_bytes(&mut buf);
11620 let mut unstructured = Unstructured::new(&buf);
11621 Self::arbitrary(&mut unstructured).unwrap_or_default()
11622 }
11623}
11624impl Default for TERRAIN_CHECK_DATA {
11625 fn default() -> Self {
11626 Self::DEFAULT.clone()
11627 }
11628}
11629impl MessageData for TERRAIN_CHECK_DATA {
11630 type Message = MavMessage;
11631 const ID: u32 = 135u32;
11632 const NAME: &'static str = "TERRAIN_CHECK";
11633 const EXTRA_CRC: u8 = 203u8;
11634 const ENCODED_LEN: usize = 8usize;
11635 fn deser(
11636 _version: MavlinkVersion,
11637 __input: &[u8],
11638 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11639 let avail_len = __input.len();
11640 let mut payload_buf = [0; Self::ENCODED_LEN];
11641 let mut buf = if avail_len < Self::ENCODED_LEN {
11642 payload_buf[0..avail_len].copy_from_slice(__input);
11643 Bytes::new(&payload_buf)
11644 } else {
11645 Bytes::new(__input)
11646 };
11647 let mut __struct = Self::default();
11648 __struct.lat = buf.get_i32_le();
11649 __struct.lon = buf.get_i32_le();
11650 Ok(__struct)
11651 }
11652 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11653 let mut __tmp = BytesMut::new(bytes);
11654 #[allow(clippy::absurd_extreme_comparisons)]
11655 #[allow(unused_comparisons)]
11656 if __tmp.remaining() < Self::ENCODED_LEN {
11657 panic!(
11658 "buffer is too small (need {} bytes, but got {})",
11659 Self::ENCODED_LEN,
11660 __tmp.remaining(),
11661 )
11662 }
11663 __tmp.put_i32_le(self.lat);
11664 __tmp.put_i32_le(self.lon);
11665 if matches!(version, MavlinkVersion::V2) {
11666 let len = __tmp.len();
11667 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11668 } else {
11669 __tmp.len()
11670 }
11671 }
11672}
11673#[doc = "id: 67"]
11674#[doc = "Data stream status information."]
11675#[derive(Debug, Clone, PartialEq)]
11676#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11677#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11678pub struct DATA_STREAM_DATA {
11679 #[doc = "The message rate"]
11680 pub message_rate: u16,
11681 #[doc = "The ID of the requested data stream"]
11682 pub stream_id: u8,
11683 #[doc = "1 stream is enabled, 0 stream is stopped."]
11684 pub on_off: u8,
11685}
11686impl DATA_STREAM_DATA {
11687 pub const ENCODED_LEN: usize = 4usize;
11688 pub const DEFAULT: Self = Self {
11689 message_rate: 0_u16,
11690 stream_id: 0_u8,
11691 on_off: 0_u8,
11692 };
11693 #[cfg(feature = "arbitrary")]
11694 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11695 use arbitrary::{Arbitrary, Unstructured};
11696 let mut buf = [0u8; 1024];
11697 rng.fill_bytes(&mut buf);
11698 let mut unstructured = Unstructured::new(&buf);
11699 Self::arbitrary(&mut unstructured).unwrap_or_default()
11700 }
11701}
11702impl Default for DATA_STREAM_DATA {
11703 fn default() -> Self {
11704 Self::DEFAULT.clone()
11705 }
11706}
11707impl MessageData for DATA_STREAM_DATA {
11708 type Message = MavMessage;
11709 const ID: u32 = 67u32;
11710 const NAME: &'static str = "DATA_STREAM";
11711 const EXTRA_CRC: u8 = 21u8;
11712 const ENCODED_LEN: usize = 4usize;
11713 fn deser(
11714 _version: MavlinkVersion,
11715 __input: &[u8],
11716 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11717 let avail_len = __input.len();
11718 let mut payload_buf = [0; Self::ENCODED_LEN];
11719 let mut buf = if avail_len < Self::ENCODED_LEN {
11720 payload_buf[0..avail_len].copy_from_slice(__input);
11721 Bytes::new(&payload_buf)
11722 } else {
11723 Bytes::new(__input)
11724 };
11725 let mut __struct = Self::default();
11726 __struct.message_rate = buf.get_u16_le();
11727 __struct.stream_id = buf.get_u8();
11728 __struct.on_off = buf.get_u8();
11729 Ok(__struct)
11730 }
11731 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11732 let mut __tmp = BytesMut::new(bytes);
11733 #[allow(clippy::absurd_extreme_comparisons)]
11734 #[allow(unused_comparisons)]
11735 if __tmp.remaining() < Self::ENCODED_LEN {
11736 panic!(
11737 "buffer is too small (need {} bytes, but got {})",
11738 Self::ENCODED_LEN,
11739 __tmp.remaining(),
11740 )
11741 }
11742 __tmp.put_u16_le(self.message_rate);
11743 __tmp.put_u8(self.stream_id);
11744 __tmp.put_u8(self.on_off);
11745 if matches!(version, MavlinkVersion::V2) {
11746 let len = __tmp.len();
11747 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11748 } else {
11749 __tmp.len()
11750 }
11751 }
11752}
11753#[doc = "id: 117"]
11754#[doc = "Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0."]
11755#[derive(Debug, Clone, PartialEq)]
11756#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11757#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11758pub struct LOG_REQUEST_LIST_DATA {
11759 #[doc = "First log id (0 for first available)"]
11760 pub start: u16,
11761 #[doc = "Last log id (0xffff for last available)"]
11762 pub end: u16,
11763 #[doc = "System ID"]
11764 pub target_system: u8,
11765 #[doc = "Component ID"]
11766 pub target_component: u8,
11767}
11768impl LOG_REQUEST_LIST_DATA {
11769 pub const ENCODED_LEN: usize = 6usize;
11770 pub const DEFAULT: Self = Self {
11771 start: 0_u16,
11772 end: 0_u16,
11773 target_system: 0_u8,
11774 target_component: 0_u8,
11775 };
11776 #[cfg(feature = "arbitrary")]
11777 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11778 use arbitrary::{Arbitrary, Unstructured};
11779 let mut buf = [0u8; 1024];
11780 rng.fill_bytes(&mut buf);
11781 let mut unstructured = Unstructured::new(&buf);
11782 Self::arbitrary(&mut unstructured).unwrap_or_default()
11783 }
11784}
11785impl Default for LOG_REQUEST_LIST_DATA {
11786 fn default() -> Self {
11787 Self::DEFAULT.clone()
11788 }
11789}
11790impl MessageData for LOG_REQUEST_LIST_DATA {
11791 type Message = MavMessage;
11792 const ID: u32 = 117u32;
11793 const NAME: &'static str = "LOG_REQUEST_LIST";
11794 const EXTRA_CRC: u8 = 128u8;
11795 const ENCODED_LEN: usize = 6usize;
11796 fn deser(
11797 _version: MavlinkVersion,
11798 __input: &[u8],
11799 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11800 let avail_len = __input.len();
11801 let mut payload_buf = [0; Self::ENCODED_LEN];
11802 let mut buf = if avail_len < Self::ENCODED_LEN {
11803 payload_buf[0..avail_len].copy_from_slice(__input);
11804 Bytes::new(&payload_buf)
11805 } else {
11806 Bytes::new(__input)
11807 };
11808 let mut __struct = Self::default();
11809 __struct.start = buf.get_u16_le();
11810 __struct.end = buf.get_u16_le();
11811 __struct.target_system = buf.get_u8();
11812 __struct.target_component = buf.get_u8();
11813 Ok(__struct)
11814 }
11815 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11816 let mut __tmp = BytesMut::new(bytes);
11817 #[allow(clippy::absurd_extreme_comparisons)]
11818 #[allow(unused_comparisons)]
11819 if __tmp.remaining() < Self::ENCODED_LEN {
11820 panic!(
11821 "buffer is too small (need {} bytes, but got {})",
11822 Self::ENCODED_LEN,
11823 __tmp.remaining(),
11824 )
11825 }
11826 __tmp.put_u16_le(self.start);
11827 __tmp.put_u16_le(self.end);
11828 __tmp.put_u8(self.target_system);
11829 __tmp.put_u8(self.target_component);
11830 if matches!(version, MavlinkVersion::V2) {
11831 let len = __tmp.len();
11832 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11833 } else {
11834 __tmp.len()
11835 }
11836 }
11837}
11838#[doc = "id: 245"]
11839#[doc = "Provides state for additional features."]
11840#[derive(Debug, Clone, PartialEq)]
11841#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11842#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11843pub struct EXTENDED_SYS_STATE_DATA {
11844 #[doc = "The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration."]
11845 pub vtol_state: MavVtolState,
11846 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
11847 pub landed_state: MavLandedState,
11848}
11849impl EXTENDED_SYS_STATE_DATA {
11850 pub const ENCODED_LEN: usize = 2usize;
11851 pub const DEFAULT: Self = Self {
11852 vtol_state: MavVtolState::DEFAULT,
11853 landed_state: MavLandedState::DEFAULT,
11854 };
11855 #[cfg(feature = "arbitrary")]
11856 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11857 use arbitrary::{Arbitrary, Unstructured};
11858 let mut buf = [0u8; 1024];
11859 rng.fill_bytes(&mut buf);
11860 let mut unstructured = Unstructured::new(&buf);
11861 Self::arbitrary(&mut unstructured).unwrap_or_default()
11862 }
11863}
11864impl Default for EXTENDED_SYS_STATE_DATA {
11865 fn default() -> Self {
11866 Self::DEFAULT.clone()
11867 }
11868}
11869impl MessageData for EXTENDED_SYS_STATE_DATA {
11870 type Message = MavMessage;
11871 const ID: u32 = 245u32;
11872 const NAME: &'static str = "EXTENDED_SYS_STATE";
11873 const EXTRA_CRC: u8 = 130u8;
11874 const ENCODED_LEN: usize = 2usize;
11875 fn deser(
11876 _version: MavlinkVersion,
11877 __input: &[u8],
11878 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11879 let avail_len = __input.len();
11880 let mut payload_buf = [0; Self::ENCODED_LEN];
11881 let mut buf = if avail_len < Self::ENCODED_LEN {
11882 payload_buf[0..avail_len].copy_from_slice(__input);
11883 Bytes::new(&payload_buf)
11884 } else {
11885 Bytes::new(__input)
11886 };
11887 let mut __struct = Self::default();
11888 let tmp = buf.get_u8();
11889 __struct.vtol_state =
11890 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11891 enum_type: "MavVtolState",
11892 value: tmp as u32,
11893 })?;
11894 let tmp = buf.get_u8();
11895 __struct.landed_state =
11896 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11897 enum_type: "MavLandedState",
11898 value: tmp as u32,
11899 })?;
11900 Ok(__struct)
11901 }
11902 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11903 let mut __tmp = BytesMut::new(bytes);
11904 #[allow(clippy::absurd_extreme_comparisons)]
11905 #[allow(unused_comparisons)]
11906 if __tmp.remaining() < Self::ENCODED_LEN {
11907 panic!(
11908 "buffer is too small (need {} bytes, but got {})",
11909 Self::ENCODED_LEN,
11910 __tmp.remaining(),
11911 )
11912 }
11913 __tmp.put_u8(self.vtol_state as u8);
11914 __tmp.put_u8(self.landed_state as u8);
11915 if matches!(version, MavlinkVersion::V2) {
11916 let len = __tmp.len();
11917 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11918 } else {
11919 __tmp.len()
11920 }
11921 }
11922}
11923#[doc = "id: 112"]
11924#[doc = "Camera-IMU triggering and synchronisation message."]
11925#[derive(Debug, Clone, PartialEq)]
11926#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11927#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11928pub struct CAMERA_TRIGGER_DATA {
11929 #[doc = "Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
11930 pub time_usec: u64,
11931 #[doc = "Image frame sequence"]
11932 pub seq: u32,
11933}
11934impl CAMERA_TRIGGER_DATA {
11935 pub const ENCODED_LEN: usize = 12usize;
11936 pub const DEFAULT: Self = Self {
11937 time_usec: 0_u64,
11938 seq: 0_u32,
11939 };
11940 #[cfg(feature = "arbitrary")]
11941 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11942 use arbitrary::{Arbitrary, Unstructured};
11943 let mut buf = [0u8; 1024];
11944 rng.fill_bytes(&mut buf);
11945 let mut unstructured = Unstructured::new(&buf);
11946 Self::arbitrary(&mut unstructured).unwrap_or_default()
11947 }
11948}
11949impl Default for CAMERA_TRIGGER_DATA {
11950 fn default() -> Self {
11951 Self::DEFAULT.clone()
11952 }
11953}
11954impl MessageData for CAMERA_TRIGGER_DATA {
11955 type Message = MavMessage;
11956 const ID: u32 = 112u32;
11957 const NAME: &'static str = "CAMERA_TRIGGER";
11958 const EXTRA_CRC: u8 = 174u8;
11959 const ENCODED_LEN: usize = 12usize;
11960 fn deser(
11961 _version: MavlinkVersion,
11962 __input: &[u8],
11963 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11964 let avail_len = __input.len();
11965 let mut payload_buf = [0; Self::ENCODED_LEN];
11966 let mut buf = if avail_len < Self::ENCODED_LEN {
11967 payload_buf[0..avail_len].copy_from_slice(__input);
11968 Bytes::new(&payload_buf)
11969 } else {
11970 Bytes::new(__input)
11971 };
11972 let mut __struct = Self::default();
11973 __struct.time_usec = buf.get_u64_le();
11974 __struct.seq = buf.get_u32_le();
11975 Ok(__struct)
11976 }
11977 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11978 let mut __tmp = BytesMut::new(bytes);
11979 #[allow(clippy::absurd_extreme_comparisons)]
11980 #[allow(unused_comparisons)]
11981 if __tmp.remaining() < Self::ENCODED_LEN {
11982 panic!(
11983 "buffer is too small (need {} bytes, but got {})",
11984 Self::ENCODED_LEN,
11985 __tmp.remaining(),
11986 )
11987 }
11988 __tmp.put_u64_le(self.time_usec);
11989 __tmp.put_u32_le(self.seq);
11990 if matches!(version, MavlinkVersion::V2) {
11991 let len = __tmp.len();
11992 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11993 } else {
11994 __tmp.len()
11995 }
11996 }
11997}
11998#[doc = "id: 244"]
11999#[doc = "The interval between messages for a particular MAVLink message ID. This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). \tIt may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. \tThis interface replaces DATA_STREAM."]
12000#[derive(Debug, Clone, PartialEq)]
12001#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12002#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12003pub struct MESSAGE_INTERVAL_DATA {
12004 #[doc = "0 indicates the interval at which it is sent."]
12005 pub interval_us: i32,
12006 #[doc = "The ID of the requested MAVLink message. v1.0 is limited to 254 messages."]
12007 pub message_id: u16,
12008}
12009impl MESSAGE_INTERVAL_DATA {
12010 pub const ENCODED_LEN: usize = 6usize;
12011 pub const DEFAULT: Self = Self {
12012 interval_us: 0_i32,
12013 message_id: 0_u16,
12014 };
12015 #[cfg(feature = "arbitrary")]
12016 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12017 use arbitrary::{Arbitrary, Unstructured};
12018 let mut buf = [0u8; 1024];
12019 rng.fill_bytes(&mut buf);
12020 let mut unstructured = Unstructured::new(&buf);
12021 Self::arbitrary(&mut unstructured).unwrap_or_default()
12022 }
12023}
12024impl Default for MESSAGE_INTERVAL_DATA {
12025 fn default() -> Self {
12026 Self::DEFAULT.clone()
12027 }
12028}
12029impl MessageData for MESSAGE_INTERVAL_DATA {
12030 type Message = MavMessage;
12031 const ID: u32 = 244u32;
12032 const NAME: &'static str = "MESSAGE_INTERVAL";
12033 const EXTRA_CRC: u8 = 95u8;
12034 const ENCODED_LEN: usize = 6usize;
12035 fn deser(
12036 _version: MavlinkVersion,
12037 __input: &[u8],
12038 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12039 let avail_len = __input.len();
12040 let mut payload_buf = [0; Self::ENCODED_LEN];
12041 let mut buf = if avail_len < Self::ENCODED_LEN {
12042 payload_buf[0..avail_len].copy_from_slice(__input);
12043 Bytes::new(&payload_buf)
12044 } else {
12045 Bytes::new(__input)
12046 };
12047 let mut __struct = Self::default();
12048 __struct.interval_us = buf.get_i32_le();
12049 __struct.message_id = buf.get_u16_le();
12050 Ok(__struct)
12051 }
12052 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12053 let mut __tmp = BytesMut::new(bytes);
12054 #[allow(clippy::absurd_extreme_comparisons)]
12055 #[allow(unused_comparisons)]
12056 if __tmp.remaining() < Self::ENCODED_LEN {
12057 panic!(
12058 "buffer is too small (need {} bytes, but got {})",
12059 Self::ENCODED_LEN,
12060 __tmp.remaining(),
12061 )
12062 }
12063 __tmp.put_i32_le(self.interval_us);
12064 __tmp.put_u16_le(self.message_id);
12065 if matches!(version, MavlinkVersion::V2) {
12066 let len = __tmp.len();
12067 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12068 } else {
12069 __tmp.len()
12070 }
12071 }
12072}
12073#[doc = "id: 123"]
12074#[doc = "Data for injecting into the onboard GPS (used for DGPS)."]
12075#[derive(Debug, Clone, PartialEq)]
12076#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12077#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12078pub struct GPS_INJECT_DATA_DATA {
12079 #[doc = "System ID"]
12080 pub target_system: u8,
12081 #[doc = "Component ID"]
12082 pub target_component: u8,
12083 #[doc = "Data length"]
12084 pub len: u8,
12085 #[doc = "Raw data (110 is enough for 12 satellites of RTCMv2)"]
12086 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12087 pub data: [u8; 110],
12088}
12089impl GPS_INJECT_DATA_DATA {
12090 pub const ENCODED_LEN: usize = 113usize;
12091 pub const DEFAULT: Self = Self {
12092 target_system: 0_u8,
12093 target_component: 0_u8,
12094 len: 0_u8,
12095 data: [0_u8; 110usize],
12096 };
12097 #[cfg(feature = "arbitrary")]
12098 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12099 use arbitrary::{Arbitrary, Unstructured};
12100 let mut buf = [0u8; 1024];
12101 rng.fill_bytes(&mut buf);
12102 let mut unstructured = Unstructured::new(&buf);
12103 Self::arbitrary(&mut unstructured).unwrap_or_default()
12104 }
12105}
12106impl Default for GPS_INJECT_DATA_DATA {
12107 fn default() -> Self {
12108 Self::DEFAULT.clone()
12109 }
12110}
12111impl MessageData for GPS_INJECT_DATA_DATA {
12112 type Message = MavMessage;
12113 const ID: u32 = 123u32;
12114 const NAME: &'static str = "GPS_INJECT_DATA";
12115 const EXTRA_CRC: u8 = 250u8;
12116 const ENCODED_LEN: usize = 113usize;
12117 fn deser(
12118 _version: MavlinkVersion,
12119 __input: &[u8],
12120 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12121 let avail_len = __input.len();
12122 let mut payload_buf = [0; Self::ENCODED_LEN];
12123 let mut buf = if avail_len < Self::ENCODED_LEN {
12124 payload_buf[0..avail_len].copy_from_slice(__input);
12125 Bytes::new(&payload_buf)
12126 } else {
12127 Bytes::new(__input)
12128 };
12129 let mut __struct = Self::default();
12130 __struct.target_system = buf.get_u8();
12131 __struct.target_component = buf.get_u8();
12132 __struct.len = buf.get_u8();
12133 for v in &mut __struct.data {
12134 let val = buf.get_u8();
12135 *v = val;
12136 }
12137 Ok(__struct)
12138 }
12139 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12140 let mut __tmp = BytesMut::new(bytes);
12141 #[allow(clippy::absurd_extreme_comparisons)]
12142 #[allow(unused_comparisons)]
12143 if __tmp.remaining() < Self::ENCODED_LEN {
12144 panic!(
12145 "buffer is too small (need {} bytes, but got {})",
12146 Self::ENCODED_LEN,
12147 __tmp.remaining(),
12148 )
12149 }
12150 __tmp.put_u8(self.target_system);
12151 __tmp.put_u8(self.target_component);
12152 __tmp.put_u8(self.len);
12153 for val in &self.data {
12154 __tmp.put_u8(*val);
12155 }
12156 if matches!(version, MavlinkVersion::V2) {
12157 let len = __tmp.len();
12158 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12159 } else {
12160 __tmp.len()
12161 }
12162 }
12163}
12164#[doc = "id: 242"]
12165#[doc = "Contains the home position. \tThe home position is the default position that the system will return to and land on. \tThe position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. \tThe global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. \tUnder normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. \tThe approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command)."]
12166#[derive(Debug, Clone, PartialEq)]
12167#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12168#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12169pub struct HOME_POSITION_DATA {
12170 #[doc = "Latitude (WGS84)"]
12171 pub latitude: i32,
12172 #[doc = "Longitude (WGS84)"]
12173 pub longitude: i32,
12174 #[doc = "Altitude (MSL). Positive for up."]
12175 pub altitude: i32,
12176 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
12177 pub x: f32,
12178 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
12179 pub y: f32,
12180 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
12181 pub z: f32,
12182 #[doc = "Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied."]
12183 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12184 pub q: [f32; 4],
12185 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
12186 pub approach_x: f32,
12187 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
12188 pub approach_y: f32,
12189 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
12190 pub approach_z: f32,
12191 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
12192 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12193 pub time_usec: u64,
12194}
12195impl HOME_POSITION_DATA {
12196 pub const ENCODED_LEN: usize = 60usize;
12197 pub const DEFAULT: Self = Self {
12198 latitude: 0_i32,
12199 longitude: 0_i32,
12200 altitude: 0_i32,
12201 x: 0.0_f32,
12202 y: 0.0_f32,
12203 z: 0.0_f32,
12204 q: [0.0_f32; 4usize],
12205 approach_x: 0.0_f32,
12206 approach_y: 0.0_f32,
12207 approach_z: 0.0_f32,
12208 time_usec: 0_u64,
12209 };
12210 #[cfg(feature = "arbitrary")]
12211 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12212 use arbitrary::{Arbitrary, Unstructured};
12213 let mut buf = [0u8; 1024];
12214 rng.fill_bytes(&mut buf);
12215 let mut unstructured = Unstructured::new(&buf);
12216 Self::arbitrary(&mut unstructured).unwrap_or_default()
12217 }
12218}
12219impl Default for HOME_POSITION_DATA {
12220 fn default() -> Self {
12221 Self::DEFAULT.clone()
12222 }
12223}
12224impl MessageData for HOME_POSITION_DATA {
12225 type Message = MavMessage;
12226 const ID: u32 = 242u32;
12227 const NAME: &'static str = "HOME_POSITION";
12228 const EXTRA_CRC: u8 = 104u8;
12229 const ENCODED_LEN: usize = 60usize;
12230 fn deser(
12231 _version: MavlinkVersion,
12232 __input: &[u8],
12233 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12234 let avail_len = __input.len();
12235 let mut payload_buf = [0; Self::ENCODED_LEN];
12236 let mut buf = if avail_len < Self::ENCODED_LEN {
12237 payload_buf[0..avail_len].copy_from_slice(__input);
12238 Bytes::new(&payload_buf)
12239 } else {
12240 Bytes::new(__input)
12241 };
12242 let mut __struct = Self::default();
12243 __struct.latitude = buf.get_i32_le();
12244 __struct.longitude = buf.get_i32_le();
12245 __struct.altitude = buf.get_i32_le();
12246 __struct.x = buf.get_f32_le();
12247 __struct.y = buf.get_f32_le();
12248 __struct.z = buf.get_f32_le();
12249 for v in &mut __struct.q {
12250 let val = buf.get_f32_le();
12251 *v = val;
12252 }
12253 __struct.approach_x = buf.get_f32_le();
12254 __struct.approach_y = buf.get_f32_le();
12255 __struct.approach_z = buf.get_f32_le();
12256 __struct.time_usec = buf.get_u64_le();
12257 Ok(__struct)
12258 }
12259 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12260 let mut __tmp = BytesMut::new(bytes);
12261 #[allow(clippy::absurd_extreme_comparisons)]
12262 #[allow(unused_comparisons)]
12263 if __tmp.remaining() < Self::ENCODED_LEN {
12264 panic!(
12265 "buffer is too small (need {} bytes, but got {})",
12266 Self::ENCODED_LEN,
12267 __tmp.remaining(),
12268 )
12269 }
12270 __tmp.put_i32_le(self.latitude);
12271 __tmp.put_i32_le(self.longitude);
12272 __tmp.put_i32_le(self.altitude);
12273 __tmp.put_f32_le(self.x);
12274 __tmp.put_f32_le(self.y);
12275 __tmp.put_f32_le(self.z);
12276 for val in &self.q {
12277 __tmp.put_f32_le(*val);
12278 }
12279 __tmp.put_f32_le(self.approach_x);
12280 __tmp.put_f32_le(self.approach_y);
12281 __tmp.put_f32_le(self.approach_z);
12282 __tmp.put_u64_le(self.time_usec);
12283 if matches!(version, MavlinkVersion::V2) {
12284 let len = __tmp.len();
12285 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12286 } else {
12287 __tmp.len()
12288 }
12289 }
12290}
12291#[doc = "id: 50"]
12292#[doc = "Bind a RC channel to a parameter. The parameter should change according to the RC channel value."]
12293#[derive(Debug, Clone, PartialEq)]
12294#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12295#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12296pub struct PARAM_MAP_RC_DATA {
12297 #[doc = "Initial parameter value"]
12298 pub param_value0: f32,
12299 #[doc = "Scale, maps the RC range [-1, 1] to a parameter value"]
12300 pub scale: f32,
12301 #[doc = "Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)"]
12302 pub param_value_min: f32,
12303 #[doc = "Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)"]
12304 pub param_value_max: f32,
12305 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index."]
12306 pub param_index: i16,
12307 #[doc = "System ID"]
12308 pub target_system: u8,
12309 #[doc = "Component ID"]
12310 pub target_component: u8,
12311 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
12312 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12313 pub param_id: [u8; 16],
12314 #[doc = "Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC."]
12315 pub parameter_rc_channel_index: u8,
12316}
12317impl PARAM_MAP_RC_DATA {
12318 pub const ENCODED_LEN: usize = 37usize;
12319 pub const DEFAULT: Self = Self {
12320 param_value0: 0.0_f32,
12321 scale: 0.0_f32,
12322 param_value_min: 0.0_f32,
12323 param_value_max: 0.0_f32,
12324 param_index: 0_i16,
12325 target_system: 0_u8,
12326 target_component: 0_u8,
12327 param_id: [0_u8; 16usize],
12328 parameter_rc_channel_index: 0_u8,
12329 };
12330 #[cfg(feature = "arbitrary")]
12331 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12332 use arbitrary::{Arbitrary, Unstructured};
12333 let mut buf = [0u8; 1024];
12334 rng.fill_bytes(&mut buf);
12335 let mut unstructured = Unstructured::new(&buf);
12336 Self::arbitrary(&mut unstructured).unwrap_or_default()
12337 }
12338}
12339impl Default for PARAM_MAP_RC_DATA {
12340 fn default() -> Self {
12341 Self::DEFAULT.clone()
12342 }
12343}
12344impl MessageData for PARAM_MAP_RC_DATA {
12345 type Message = MavMessage;
12346 const ID: u32 = 50u32;
12347 const NAME: &'static str = "PARAM_MAP_RC";
12348 const EXTRA_CRC: u8 = 78u8;
12349 const ENCODED_LEN: usize = 37usize;
12350 fn deser(
12351 _version: MavlinkVersion,
12352 __input: &[u8],
12353 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12354 let avail_len = __input.len();
12355 let mut payload_buf = [0; Self::ENCODED_LEN];
12356 let mut buf = if avail_len < Self::ENCODED_LEN {
12357 payload_buf[0..avail_len].copy_from_slice(__input);
12358 Bytes::new(&payload_buf)
12359 } else {
12360 Bytes::new(__input)
12361 };
12362 let mut __struct = Self::default();
12363 __struct.param_value0 = buf.get_f32_le();
12364 __struct.scale = buf.get_f32_le();
12365 __struct.param_value_min = buf.get_f32_le();
12366 __struct.param_value_max = buf.get_f32_le();
12367 __struct.param_index = buf.get_i16_le();
12368 __struct.target_system = buf.get_u8();
12369 __struct.target_component = buf.get_u8();
12370 for v in &mut __struct.param_id {
12371 let val = buf.get_u8();
12372 *v = val;
12373 }
12374 __struct.parameter_rc_channel_index = buf.get_u8();
12375 Ok(__struct)
12376 }
12377 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12378 let mut __tmp = BytesMut::new(bytes);
12379 #[allow(clippy::absurd_extreme_comparisons)]
12380 #[allow(unused_comparisons)]
12381 if __tmp.remaining() < Self::ENCODED_LEN {
12382 panic!(
12383 "buffer is too small (need {} bytes, but got {})",
12384 Self::ENCODED_LEN,
12385 __tmp.remaining(),
12386 )
12387 }
12388 __tmp.put_f32_le(self.param_value0);
12389 __tmp.put_f32_le(self.scale);
12390 __tmp.put_f32_le(self.param_value_min);
12391 __tmp.put_f32_le(self.param_value_max);
12392 __tmp.put_i16_le(self.param_index);
12393 __tmp.put_u8(self.target_system);
12394 __tmp.put_u8(self.target_component);
12395 for val in &self.param_id {
12396 __tmp.put_u8(*val);
12397 }
12398 __tmp.put_u8(self.parameter_rc_channel_index);
12399 if matches!(version, MavlinkVersion::V2) {
12400 let len = __tmp.len();
12401 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12402 } else {
12403 __tmp.len()
12404 }
12405 }
12406}
12407#[doc = "id: 126"]
12408#[doc = "Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate."]
12409#[derive(Debug, Clone, PartialEq)]
12410#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12411#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12412pub struct SERIAL_CONTROL_DATA {
12413 #[doc = "Baudrate of transfer. Zero means no change."]
12414 pub baudrate: u32,
12415 #[doc = "Timeout for reply data"]
12416 pub timeout: u16,
12417 #[doc = "Serial control device type."]
12418 pub device: SerialControlDev,
12419 #[doc = "Bitmap of serial control flags."]
12420 pub flags: SerialControlFlag,
12421 #[doc = "how many bytes in this transfer"]
12422 pub count: u8,
12423 #[doc = "serial data"]
12424 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12425 pub data: [u8; 70],
12426 #[doc = "System ID"]
12427 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12428 pub target_system: u8,
12429 #[doc = "Component ID"]
12430 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12431 pub target_component: u8,
12432}
12433impl SERIAL_CONTROL_DATA {
12434 pub const ENCODED_LEN: usize = 81usize;
12435 pub const DEFAULT: Self = Self {
12436 baudrate: 0_u32,
12437 timeout: 0_u16,
12438 device: SerialControlDev::DEFAULT,
12439 flags: SerialControlFlag::DEFAULT,
12440 count: 0_u8,
12441 data: [0_u8; 70usize],
12442 target_system: 0_u8,
12443 target_component: 0_u8,
12444 };
12445 #[cfg(feature = "arbitrary")]
12446 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12447 use arbitrary::{Arbitrary, Unstructured};
12448 let mut buf = [0u8; 1024];
12449 rng.fill_bytes(&mut buf);
12450 let mut unstructured = Unstructured::new(&buf);
12451 Self::arbitrary(&mut unstructured).unwrap_or_default()
12452 }
12453}
12454impl Default for SERIAL_CONTROL_DATA {
12455 fn default() -> Self {
12456 Self::DEFAULT.clone()
12457 }
12458}
12459impl MessageData for SERIAL_CONTROL_DATA {
12460 type Message = MavMessage;
12461 const ID: u32 = 126u32;
12462 const NAME: &'static str = "SERIAL_CONTROL";
12463 const EXTRA_CRC: u8 = 220u8;
12464 const ENCODED_LEN: usize = 81usize;
12465 fn deser(
12466 _version: MavlinkVersion,
12467 __input: &[u8],
12468 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12469 let avail_len = __input.len();
12470 let mut payload_buf = [0; Self::ENCODED_LEN];
12471 let mut buf = if avail_len < Self::ENCODED_LEN {
12472 payload_buf[0..avail_len].copy_from_slice(__input);
12473 Bytes::new(&payload_buf)
12474 } else {
12475 Bytes::new(__input)
12476 };
12477 let mut __struct = Self::default();
12478 __struct.baudrate = buf.get_u32_le();
12479 __struct.timeout = buf.get_u16_le();
12480 let tmp = buf.get_u8();
12481 __struct.device =
12482 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12483 enum_type: "SerialControlDev",
12484 value: tmp as u32,
12485 })?;
12486 let tmp = buf.get_u8();
12487 __struct.flags = SerialControlFlag::from_bits(tmp & SerialControlFlag::all().bits())
12488 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
12489 flag_type: "SerialControlFlag",
12490 value: tmp as u32,
12491 })?;
12492 __struct.count = buf.get_u8();
12493 for v in &mut __struct.data {
12494 let val = buf.get_u8();
12495 *v = val;
12496 }
12497 __struct.target_system = buf.get_u8();
12498 __struct.target_component = buf.get_u8();
12499 Ok(__struct)
12500 }
12501 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12502 let mut __tmp = BytesMut::new(bytes);
12503 #[allow(clippy::absurd_extreme_comparisons)]
12504 #[allow(unused_comparisons)]
12505 if __tmp.remaining() < Self::ENCODED_LEN {
12506 panic!(
12507 "buffer is too small (need {} bytes, but got {})",
12508 Self::ENCODED_LEN,
12509 __tmp.remaining(),
12510 )
12511 }
12512 __tmp.put_u32_le(self.baudrate);
12513 __tmp.put_u16_le(self.timeout);
12514 __tmp.put_u8(self.device as u8);
12515 __tmp.put_u8(self.flags.bits());
12516 __tmp.put_u8(self.count);
12517 for val in &self.data {
12518 __tmp.put_u8(*val);
12519 }
12520 __tmp.put_u8(self.target_system);
12521 __tmp.put_u8(self.target_component);
12522 if matches!(version, MavlinkVersion::V2) {
12523 let len = __tmp.len();
12524 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12525 } else {
12526 __tmp.len()
12527 }
12528 }
12529}
12530#[doc = "id: 12901"]
12531#[doc = "Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft."]
12532#[derive(Debug, Clone, PartialEq)]
12533#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12534#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12535pub struct OPEN_DRONE_ID_LOCATION_DATA {
12536 #[doc = "Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
12537 pub latitude: i32,
12538 #[doc = "Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
12539 pub longitude: i32,
12540 #[doc = "The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m."]
12541 pub altitude_barometric: f32,
12542 #[doc = "The geodetic altitude as defined by WGS84. If unknown: -1000 m."]
12543 pub altitude_geodetic: f32,
12544 #[doc = "The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m."]
12545 pub height: f32,
12546 #[doc = "Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF."]
12547 pub timestamp: f32,
12548 #[doc = "Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees."]
12549 pub direction: u16,
12550 #[doc = "Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s."]
12551 pub speed_horizontal: u16,
12552 #[doc = "The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s."]
12553 pub speed_vertical: i16,
12554 #[doc = "System ID (0 for broadcast)."]
12555 pub target_system: u8,
12556 #[doc = "Component ID (0 for broadcast)."]
12557 pub target_component: u8,
12558 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
12559 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12560 pub id_or_mac: [u8; 20],
12561 #[doc = "Indicates whether the unmanned aircraft is on the ground or in the air."]
12562 pub status: MavOdidStatus,
12563 #[doc = "Indicates the reference point for the height field."]
12564 pub height_reference: MavOdidHeightRef,
12565 #[doc = "The accuracy of the horizontal position."]
12566 pub horizontal_accuracy: MavOdidHorAcc,
12567 #[doc = "The accuracy of the vertical position."]
12568 pub vertical_accuracy: MavOdidVerAcc,
12569 #[doc = "The accuracy of the barometric altitude."]
12570 pub barometer_accuracy: MavOdidVerAcc,
12571 #[doc = "The accuracy of the horizontal and vertical speed."]
12572 pub speed_accuracy: MavOdidSpeedAcc,
12573 #[doc = "The accuracy of the timestamps."]
12574 pub timestamp_accuracy: MavOdidTimeAcc,
12575}
12576impl OPEN_DRONE_ID_LOCATION_DATA {
12577 pub const ENCODED_LEN: usize = 59usize;
12578 pub const DEFAULT: Self = Self {
12579 latitude: 0_i32,
12580 longitude: 0_i32,
12581 altitude_barometric: 0.0_f32,
12582 altitude_geodetic: 0.0_f32,
12583 height: 0.0_f32,
12584 timestamp: 0.0_f32,
12585 direction: 0_u16,
12586 speed_horizontal: 0_u16,
12587 speed_vertical: 0_i16,
12588 target_system: 0_u8,
12589 target_component: 0_u8,
12590 id_or_mac: [0_u8; 20usize],
12591 status: MavOdidStatus::DEFAULT,
12592 height_reference: MavOdidHeightRef::DEFAULT,
12593 horizontal_accuracy: MavOdidHorAcc::DEFAULT,
12594 vertical_accuracy: MavOdidVerAcc::DEFAULT,
12595 barometer_accuracy: MavOdidVerAcc::DEFAULT,
12596 speed_accuracy: MavOdidSpeedAcc::DEFAULT,
12597 timestamp_accuracy: MavOdidTimeAcc::DEFAULT,
12598 };
12599 #[cfg(feature = "arbitrary")]
12600 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12601 use arbitrary::{Arbitrary, Unstructured};
12602 let mut buf = [0u8; 1024];
12603 rng.fill_bytes(&mut buf);
12604 let mut unstructured = Unstructured::new(&buf);
12605 Self::arbitrary(&mut unstructured).unwrap_or_default()
12606 }
12607}
12608impl Default for OPEN_DRONE_ID_LOCATION_DATA {
12609 fn default() -> Self {
12610 Self::DEFAULT.clone()
12611 }
12612}
12613impl MessageData for OPEN_DRONE_ID_LOCATION_DATA {
12614 type Message = MavMessage;
12615 const ID: u32 = 12901u32;
12616 const NAME: &'static str = "OPEN_DRONE_ID_LOCATION";
12617 const EXTRA_CRC: u8 = 254u8;
12618 const ENCODED_LEN: usize = 59usize;
12619 fn deser(
12620 _version: MavlinkVersion,
12621 __input: &[u8],
12622 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12623 let avail_len = __input.len();
12624 let mut payload_buf = [0; Self::ENCODED_LEN];
12625 let mut buf = if avail_len < Self::ENCODED_LEN {
12626 payload_buf[0..avail_len].copy_from_slice(__input);
12627 Bytes::new(&payload_buf)
12628 } else {
12629 Bytes::new(__input)
12630 };
12631 let mut __struct = Self::default();
12632 __struct.latitude = buf.get_i32_le();
12633 __struct.longitude = buf.get_i32_le();
12634 __struct.altitude_barometric = buf.get_f32_le();
12635 __struct.altitude_geodetic = buf.get_f32_le();
12636 __struct.height = buf.get_f32_le();
12637 __struct.timestamp = buf.get_f32_le();
12638 __struct.direction = buf.get_u16_le();
12639 __struct.speed_horizontal = buf.get_u16_le();
12640 __struct.speed_vertical = buf.get_i16_le();
12641 __struct.target_system = buf.get_u8();
12642 __struct.target_component = buf.get_u8();
12643 for v in &mut __struct.id_or_mac {
12644 let val = buf.get_u8();
12645 *v = val;
12646 }
12647 let tmp = buf.get_u8();
12648 __struct.status =
12649 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12650 enum_type: "MavOdidStatus",
12651 value: tmp as u32,
12652 })?;
12653 let tmp = buf.get_u8();
12654 __struct.height_reference =
12655 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12656 enum_type: "MavOdidHeightRef",
12657 value: tmp as u32,
12658 })?;
12659 let tmp = buf.get_u8();
12660 __struct.horizontal_accuracy =
12661 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12662 enum_type: "MavOdidHorAcc",
12663 value: tmp as u32,
12664 })?;
12665 let tmp = buf.get_u8();
12666 __struct.vertical_accuracy =
12667 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12668 enum_type: "MavOdidVerAcc",
12669 value: tmp as u32,
12670 })?;
12671 let tmp = buf.get_u8();
12672 __struct.barometer_accuracy =
12673 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12674 enum_type: "MavOdidVerAcc",
12675 value: tmp as u32,
12676 })?;
12677 let tmp = buf.get_u8();
12678 __struct.speed_accuracy =
12679 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12680 enum_type: "MavOdidSpeedAcc",
12681 value: tmp as u32,
12682 })?;
12683 let tmp = buf.get_u8();
12684 __struct.timestamp_accuracy =
12685 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12686 enum_type: "MavOdidTimeAcc",
12687 value: tmp as u32,
12688 })?;
12689 Ok(__struct)
12690 }
12691 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12692 let mut __tmp = BytesMut::new(bytes);
12693 #[allow(clippy::absurd_extreme_comparisons)]
12694 #[allow(unused_comparisons)]
12695 if __tmp.remaining() < Self::ENCODED_LEN {
12696 panic!(
12697 "buffer is too small (need {} bytes, but got {})",
12698 Self::ENCODED_LEN,
12699 __tmp.remaining(),
12700 )
12701 }
12702 __tmp.put_i32_le(self.latitude);
12703 __tmp.put_i32_le(self.longitude);
12704 __tmp.put_f32_le(self.altitude_barometric);
12705 __tmp.put_f32_le(self.altitude_geodetic);
12706 __tmp.put_f32_le(self.height);
12707 __tmp.put_f32_le(self.timestamp);
12708 __tmp.put_u16_le(self.direction);
12709 __tmp.put_u16_le(self.speed_horizontal);
12710 __tmp.put_i16_le(self.speed_vertical);
12711 __tmp.put_u8(self.target_system);
12712 __tmp.put_u8(self.target_component);
12713 for val in &self.id_or_mac {
12714 __tmp.put_u8(*val);
12715 }
12716 __tmp.put_u8(self.status as u8);
12717 __tmp.put_u8(self.height_reference as u8);
12718 __tmp.put_u8(self.horizontal_accuracy as u8);
12719 __tmp.put_u8(self.vertical_accuracy as u8);
12720 __tmp.put_u8(self.barometer_accuracy as u8);
12721 __tmp.put_u8(self.speed_accuracy as u8);
12722 __tmp.put_u8(self.timestamp_accuracy as u8);
12723 if matches!(version, MavlinkVersion::V2) {
12724 let len = __tmp.len();
12725 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12726 } else {
12727 __tmp.len()
12728 }
12729 }
12730}
12731#[doc = "id: 41"]
12732#[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode."]
12733#[derive(Debug, Clone, PartialEq)]
12734#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12735#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12736pub struct MISSION_SET_CURRENT_DATA {
12737 #[doc = "Sequence"]
12738 pub seq: u16,
12739 #[doc = "System ID"]
12740 pub target_system: u8,
12741 #[doc = "Component ID"]
12742 pub target_component: u8,
12743}
12744impl MISSION_SET_CURRENT_DATA {
12745 pub const ENCODED_LEN: usize = 4usize;
12746 pub const DEFAULT: Self = Self {
12747 seq: 0_u16,
12748 target_system: 0_u8,
12749 target_component: 0_u8,
12750 };
12751 #[cfg(feature = "arbitrary")]
12752 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12753 use arbitrary::{Arbitrary, Unstructured};
12754 let mut buf = [0u8; 1024];
12755 rng.fill_bytes(&mut buf);
12756 let mut unstructured = Unstructured::new(&buf);
12757 Self::arbitrary(&mut unstructured).unwrap_or_default()
12758 }
12759}
12760impl Default for MISSION_SET_CURRENT_DATA {
12761 fn default() -> Self {
12762 Self::DEFAULT.clone()
12763 }
12764}
12765impl MessageData for MISSION_SET_CURRENT_DATA {
12766 type Message = MavMessage;
12767 const ID: u32 = 41u32;
12768 const NAME: &'static str = "MISSION_SET_CURRENT";
12769 const EXTRA_CRC: u8 = 28u8;
12770 const ENCODED_LEN: usize = 4usize;
12771 fn deser(
12772 _version: MavlinkVersion,
12773 __input: &[u8],
12774 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12775 let avail_len = __input.len();
12776 let mut payload_buf = [0; Self::ENCODED_LEN];
12777 let mut buf = if avail_len < Self::ENCODED_LEN {
12778 payload_buf[0..avail_len].copy_from_slice(__input);
12779 Bytes::new(&payload_buf)
12780 } else {
12781 Bytes::new(__input)
12782 };
12783 let mut __struct = Self::default();
12784 __struct.seq = buf.get_u16_le();
12785 __struct.target_system = buf.get_u8();
12786 __struct.target_component = buf.get_u8();
12787 Ok(__struct)
12788 }
12789 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12790 let mut __tmp = BytesMut::new(bytes);
12791 #[allow(clippy::absurd_extreme_comparisons)]
12792 #[allow(unused_comparisons)]
12793 if __tmp.remaining() < Self::ENCODED_LEN {
12794 panic!(
12795 "buffer is too small (need {} bytes, but got {})",
12796 Self::ENCODED_LEN,
12797 __tmp.remaining(),
12798 )
12799 }
12800 __tmp.put_u16_le(self.seq);
12801 __tmp.put_u8(self.target_system);
12802 __tmp.put_u8(self.target_component);
12803 if matches!(version, MavlinkVersion::V2) {
12804 let len = __tmp.len();
12805 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12806 } else {
12807 __tmp.len()
12808 }
12809 }
12810}
12811#[doc = "id: 81"]
12812#[doc = "Setpoint in roll, pitch, yaw and thrust from the operator."]
12813#[derive(Debug, Clone, PartialEq)]
12814#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12815#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12816pub struct MANUAL_SETPOINT_DATA {
12817 #[doc = "Timestamp (time since system boot)."]
12818 pub time_boot_ms: u32,
12819 #[doc = "Desired roll rate"]
12820 pub roll: f32,
12821 #[doc = "Desired pitch rate"]
12822 pub pitch: f32,
12823 #[doc = "Desired yaw rate"]
12824 pub yaw: f32,
12825 #[doc = "Collective thrust, normalized to 0 .. 1"]
12826 pub thrust: f32,
12827 #[doc = "Flight mode switch position, 0.. 255"]
12828 pub mode_switch: u8,
12829 #[doc = "Override mode switch position, 0.. 255"]
12830 pub manual_override_switch: u8,
12831}
12832impl MANUAL_SETPOINT_DATA {
12833 pub const ENCODED_LEN: usize = 22usize;
12834 pub const DEFAULT: Self = Self {
12835 time_boot_ms: 0_u32,
12836 roll: 0.0_f32,
12837 pitch: 0.0_f32,
12838 yaw: 0.0_f32,
12839 thrust: 0.0_f32,
12840 mode_switch: 0_u8,
12841 manual_override_switch: 0_u8,
12842 };
12843 #[cfg(feature = "arbitrary")]
12844 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12845 use arbitrary::{Arbitrary, Unstructured};
12846 let mut buf = [0u8; 1024];
12847 rng.fill_bytes(&mut buf);
12848 let mut unstructured = Unstructured::new(&buf);
12849 Self::arbitrary(&mut unstructured).unwrap_or_default()
12850 }
12851}
12852impl Default for MANUAL_SETPOINT_DATA {
12853 fn default() -> Self {
12854 Self::DEFAULT.clone()
12855 }
12856}
12857impl MessageData for MANUAL_SETPOINT_DATA {
12858 type Message = MavMessage;
12859 const ID: u32 = 81u32;
12860 const NAME: &'static str = "MANUAL_SETPOINT";
12861 const EXTRA_CRC: u8 = 106u8;
12862 const ENCODED_LEN: usize = 22usize;
12863 fn deser(
12864 _version: MavlinkVersion,
12865 __input: &[u8],
12866 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12867 let avail_len = __input.len();
12868 let mut payload_buf = [0; Self::ENCODED_LEN];
12869 let mut buf = if avail_len < Self::ENCODED_LEN {
12870 payload_buf[0..avail_len].copy_from_slice(__input);
12871 Bytes::new(&payload_buf)
12872 } else {
12873 Bytes::new(__input)
12874 };
12875 let mut __struct = Self::default();
12876 __struct.time_boot_ms = buf.get_u32_le();
12877 __struct.roll = buf.get_f32_le();
12878 __struct.pitch = buf.get_f32_le();
12879 __struct.yaw = buf.get_f32_le();
12880 __struct.thrust = buf.get_f32_le();
12881 __struct.mode_switch = buf.get_u8();
12882 __struct.manual_override_switch = buf.get_u8();
12883 Ok(__struct)
12884 }
12885 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12886 let mut __tmp = BytesMut::new(bytes);
12887 #[allow(clippy::absurd_extreme_comparisons)]
12888 #[allow(unused_comparisons)]
12889 if __tmp.remaining() < Self::ENCODED_LEN {
12890 panic!(
12891 "buffer is too small (need {} bytes, but got {})",
12892 Self::ENCODED_LEN,
12893 __tmp.remaining(),
12894 )
12895 }
12896 __tmp.put_u32_le(self.time_boot_ms);
12897 __tmp.put_f32_le(self.roll);
12898 __tmp.put_f32_le(self.pitch);
12899 __tmp.put_f32_le(self.yaw);
12900 __tmp.put_f32_le(self.thrust);
12901 __tmp.put_u8(self.mode_switch);
12902 __tmp.put_u8(self.manual_override_switch);
12903 if matches!(version, MavlinkVersion::V2) {
12904 let len = __tmp.len();
12905 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12906 } else {
12907 __tmp.len()
12908 }
12909 }
12910}
12911#[doc = "id: 162"]
12912#[doc = "Status of geo-fencing. Sent in extended status stream when fencing enabled."]
12913#[derive(Debug, Clone, PartialEq)]
12914#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12915#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12916pub struct FENCE_STATUS_DATA {
12917 #[doc = "Time (since boot) of last breach."]
12918 pub breach_time: u32,
12919 #[doc = "Number of fence breaches."]
12920 pub breach_count: u16,
12921 #[doc = "Breach status (0 if currently inside fence, 1 if outside)."]
12922 pub breach_status: u8,
12923 #[doc = "Last breach type."]
12924 pub breach_type: FenceBreach,
12925 #[doc = "Active action to prevent fence breach"]
12926 #[cfg_attr(feature = "serde", serde(default))]
12927 pub breach_mitigation: FenceMitigate,
12928}
12929impl FENCE_STATUS_DATA {
12930 pub const ENCODED_LEN: usize = 9usize;
12931 pub const DEFAULT: Self = Self {
12932 breach_time: 0_u32,
12933 breach_count: 0_u16,
12934 breach_status: 0_u8,
12935 breach_type: FenceBreach::DEFAULT,
12936 breach_mitigation: FenceMitigate::DEFAULT,
12937 };
12938 #[cfg(feature = "arbitrary")]
12939 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12940 use arbitrary::{Arbitrary, Unstructured};
12941 let mut buf = [0u8; 1024];
12942 rng.fill_bytes(&mut buf);
12943 let mut unstructured = Unstructured::new(&buf);
12944 Self::arbitrary(&mut unstructured).unwrap_or_default()
12945 }
12946}
12947impl Default for FENCE_STATUS_DATA {
12948 fn default() -> Self {
12949 Self::DEFAULT.clone()
12950 }
12951}
12952impl MessageData for FENCE_STATUS_DATA {
12953 type Message = MavMessage;
12954 const ID: u32 = 162u32;
12955 const NAME: &'static str = "FENCE_STATUS";
12956 const EXTRA_CRC: u8 = 189u8;
12957 const ENCODED_LEN: usize = 9usize;
12958 fn deser(
12959 _version: MavlinkVersion,
12960 __input: &[u8],
12961 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12962 let avail_len = __input.len();
12963 let mut payload_buf = [0; Self::ENCODED_LEN];
12964 let mut buf = if avail_len < Self::ENCODED_LEN {
12965 payload_buf[0..avail_len].copy_from_slice(__input);
12966 Bytes::new(&payload_buf)
12967 } else {
12968 Bytes::new(__input)
12969 };
12970 let mut __struct = Self::default();
12971 __struct.breach_time = buf.get_u32_le();
12972 __struct.breach_count = buf.get_u16_le();
12973 __struct.breach_status = buf.get_u8();
12974 let tmp = buf.get_u8();
12975 __struct.breach_type =
12976 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12977 enum_type: "FenceBreach",
12978 value: tmp as u32,
12979 })?;
12980 let tmp = buf.get_u8();
12981 __struct.breach_mitigation =
12982 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12983 enum_type: "FenceMitigate",
12984 value: tmp as u32,
12985 })?;
12986 Ok(__struct)
12987 }
12988 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12989 let mut __tmp = BytesMut::new(bytes);
12990 #[allow(clippy::absurd_extreme_comparisons)]
12991 #[allow(unused_comparisons)]
12992 if __tmp.remaining() < Self::ENCODED_LEN {
12993 panic!(
12994 "buffer is too small (need {} bytes, but got {})",
12995 Self::ENCODED_LEN,
12996 __tmp.remaining(),
12997 )
12998 }
12999 __tmp.put_u32_le(self.breach_time);
13000 __tmp.put_u16_le(self.breach_count);
13001 __tmp.put_u8(self.breach_status);
13002 __tmp.put_u8(self.breach_type as u8);
13003 __tmp.put_u8(self.breach_mitigation as u8);
13004 if matches!(version, MavlinkVersion::V2) {
13005 let len = __tmp.len();
13006 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13007 } else {
13008 __tmp.len()
13009 }
13010 }
13011}
13012#[doc = "id: 264"]
13013#[doc = "Flight information. This includes time since boot for arm, takeoff, and land, and a flight number. Takeoff and landing values reset to zero on arm. This can be requested using MAV_CMD_REQUEST_MESSAGE. Note, some fields are misnamed - timestamps are from boot (not UTC) and the flight_uuid is a sequence number."]
13014#[derive(Debug, Clone, PartialEq)]
13015#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13016#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13017pub struct FLIGHT_INFORMATION_DATA {
13018 #[doc = "Timestamp at arming (since system boot). Set to 0 on boot. Set value on arming. Note, field is misnamed UTC."]
13019 pub arming_time_utc: u64,
13020 #[doc = "Timestamp at takeoff (since system boot). Set to 0 at boot and on arming. Note, field is misnamed UTC."]
13021 pub takeoff_time_utc: u64,
13022 #[doc = "Flight number. Note, field is misnamed UUID."]
13023 pub flight_uuid: u64,
13024 #[doc = "Timestamp (time since system boot)."]
13025 pub time_boot_ms: u32,
13026 #[doc = "Timestamp at landing (in ms since system boot). Set to 0 at boot and on arming."]
13027 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13028 pub landing_time: u32,
13029}
13030impl FLIGHT_INFORMATION_DATA {
13031 pub const ENCODED_LEN: usize = 32usize;
13032 pub const DEFAULT: Self = Self {
13033 arming_time_utc: 0_u64,
13034 takeoff_time_utc: 0_u64,
13035 flight_uuid: 0_u64,
13036 time_boot_ms: 0_u32,
13037 landing_time: 0_u32,
13038 };
13039 #[cfg(feature = "arbitrary")]
13040 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13041 use arbitrary::{Arbitrary, Unstructured};
13042 let mut buf = [0u8; 1024];
13043 rng.fill_bytes(&mut buf);
13044 let mut unstructured = Unstructured::new(&buf);
13045 Self::arbitrary(&mut unstructured).unwrap_or_default()
13046 }
13047}
13048impl Default for FLIGHT_INFORMATION_DATA {
13049 fn default() -> Self {
13050 Self::DEFAULT.clone()
13051 }
13052}
13053impl MessageData for FLIGHT_INFORMATION_DATA {
13054 type Message = MavMessage;
13055 const ID: u32 = 264u32;
13056 const NAME: &'static str = "FLIGHT_INFORMATION";
13057 const EXTRA_CRC: u8 = 49u8;
13058 const ENCODED_LEN: usize = 32usize;
13059 fn deser(
13060 _version: MavlinkVersion,
13061 __input: &[u8],
13062 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13063 let avail_len = __input.len();
13064 let mut payload_buf = [0; Self::ENCODED_LEN];
13065 let mut buf = if avail_len < Self::ENCODED_LEN {
13066 payload_buf[0..avail_len].copy_from_slice(__input);
13067 Bytes::new(&payload_buf)
13068 } else {
13069 Bytes::new(__input)
13070 };
13071 let mut __struct = Self::default();
13072 __struct.arming_time_utc = buf.get_u64_le();
13073 __struct.takeoff_time_utc = buf.get_u64_le();
13074 __struct.flight_uuid = buf.get_u64_le();
13075 __struct.time_boot_ms = buf.get_u32_le();
13076 __struct.landing_time = buf.get_u32_le();
13077 Ok(__struct)
13078 }
13079 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13080 let mut __tmp = BytesMut::new(bytes);
13081 #[allow(clippy::absurd_extreme_comparisons)]
13082 #[allow(unused_comparisons)]
13083 if __tmp.remaining() < Self::ENCODED_LEN {
13084 panic!(
13085 "buffer is too small (need {} bytes, but got {})",
13086 Self::ENCODED_LEN,
13087 __tmp.remaining(),
13088 )
13089 }
13090 __tmp.put_u64_le(self.arming_time_utc);
13091 __tmp.put_u64_le(self.takeoff_time_utc);
13092 __tmp.put_u64_le(self.flight_uuid);
13093 __tmp.put_u32_le(self.time_boot_ms);
13094 __tmp.put_u32_le(self.landing_time);
13095 if matches!(version, MavlinkVersion::V2) {
13096 let len = __tmp.len();
13097 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13098 } else {
13099 __tmp.len()
13100 }
13101 }
13102}
13103#[doc = "id: 280"]
13104#[doc = "Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE."]
13105#[derive(Debug, Clone, PartialEq)]
13106#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13107#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13108pub struct GIMBAL_MANAGER_INFORMATION_DATA {
13109 #[doc = "Timestamp (time since system boot)."]
13110 pub time_boot_ms: u32,
13111 #[doc = "Bitmap of gimbal capability flags."]
13112 pub cap_flags: GimbalManagerCapFlags,
13113 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
13114 pub roll_min: f32,
13115 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
13116 pub roll_max: f32,
13117 #[doc = "Minimum pitch angle (positive: up, negative: down)"]
13118 pub pitch_min: f32,
13119 #[doc = "Maximum pitch angle (positive: up, negative: down)"]
13120 pub pitch_max: f32,
13121 #[doc = "Minimum yaw angle (positive: to the right, negative: to the left)"]
13122 pub yaw_min: f32,
13123 #[doc = "Maximum yaw angle (positive: to the right, negative: to the left)"]
13124 pub yaw_max: f32,
13125 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
13126 pub gimbal_device_id: u8,
13127}
13128impl GIMBAL_MANAGER_INFORMATION_DATA {
13129 pub const ENCODED_LEN: usize = 33usize;
13130 pub const DEFAULT: Self = Self {
13131 time_boot_ms: 0_u32,
13132 cap_flags: GimbalManagerCapFlags::DEFAULT,
13133 roll_min: 0.0_f32,
13134 roll_max: 0.0_f32,
13135 pitch_min: 0.0_f32,
13136 pitch_max: 0.0_f32,
13137 yaw_min: 0.0_f32,
13138 yaw_max: 0.0_f32,
13139 gimbal_device_id: 0_u8,
13140 };
13141 #[cfg(feature = "arbitrary")]
13142 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13143 use arbitrary::{Arbitrary, Unstructured};
13144 let mut buf = [0u8; 1024];
13145 rng.fill_bytes(&mut buf);
13146 let mut unstructured = Unstructured::new(&buf);
13147 Self::arbitrary(&mut unstructured).unwrap_or_default()
13148 }
13149}
13150impl Default for GIMBAL_MANAGER_INFORMATION_DATA {
13151 fn default() -> Self {
13152 Self::DEFAULT.clone()
13153 }
13154}
13155impl MessageData for GIMBAL_MANAGER_INFORMATION_DATA {
13156 type Message = MavMessage;
13157 const ID: u32 = 280u32;
13158 const NAME: &'static str = "GIMBAL_MANAGER_INFORMATION";
13159 const EXTRA_CRC: u8 = 70u8;
13160 const ENCODED_LEN: usize = 33usize;
13161 fn deser(
13162 _version: MavlinkVersion,
13163 __input: &[u8],
13164 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13165 let avail_len = __input.len();
13166 let mut payload_buf = [0; Self::ENCODED_LEN];
13167 let mut buf = if avail_len < Self::ENCODED_LEN {
13168 payload_buf[0..avail_len].copy_from_slice(__input);
13169 Bytes::new(&payload_buf)
13170 } else {
13171 Bytes::new(__input)
13172 };
13173 let mut __struct = Self::default();
13174 __struct.time_boot_ms = buf.get_u32_le();
13175 let tmp = buf.get_u32_le();
13176 __struct.cap_flags = GimbalManagerCapFlags::from_bits(
13177 tmp & GimbalManagerCapFlags::all().bits(),
13178 )
13179 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
13180 flag_type: "GimbalManagerCapFlags",
13181 value: tmp as u32,
13182 })?;
13183 __struct.roll_min = buf.get_f32_le();
13184 __struct.roll_max = buf.get_f32_le();
13185 __struct.pitch_min = buf.get_f32_le();
13186 __struct.pitch_max = buf.get_f32_le();
13187 __struct.yaw_min = buf.get_f32_le();
13188 __struct.yaw_max = buf.get_f32_le();
13189 __struct.gimbal_device_id = buf.get_u8();
13190 Ok(__struct)
13191 }
13192 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13193 let mut __tmp = BytesMut::new(bytes);
13194 #[allow(clippy::absurd_extreme_comparisons)]
13195 #[allow(unused_comparisons)]
13196 if __tmp.remaining() < Self::ENCODED_LEN {
13197 panic!(
13198 "buffer is too small (need {} bytes, but got {})",
13199 Self::ENCODED_LEN,
13200 __tmp.remaining(),
13201 )
13202 }
13203 __tmp.put_u32_le(self.time_boot_ms);
13204 __tmp.put_u32_le(self.cap_flags.bits());
13205 __tmp.put_f32_le(self.roll_min);
13206 __tmp.put_f32_le(self.roll_max);
13207 __tmp.put_f32_le(self.pitch_min);
13208 __tmp.put_f32_le(self.pitch_max);
13209 __tmp.put_f32_le(self.yaw_min);
13210 __tmp.put_f32_le(self.yaw_max);
13211 __tmp.put_u8(self.gimbal_device_id);
13212 if matches!(version, MavlinkVersion::V2) {
13213 let len = __tmp.len();
13214 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13215 } else {
13216 __tmp.len()
13217 }
13218 }
13219}
13220#[doc = "id: 282"]
13221#[doc = "High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
13222#[derive(Debug, Clone, PartialEq)]
13223#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13224#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13225pub struct GIMBAL_MANAGER_SET_ATTITUDE_DATA {
13226 #[doc = "High level gimbal manager flags to use."]
13227 pub flags: GimbalManagerFlags,
13228 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)"]
13229 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13230 pub q: [f32; 4],
13231 #[doc = "X component of angular velocity, positive is rolling to the right, NaN to be ignored."]
13232 pub angular_velocity_x: f32,
13233 #[doc = "Y component of angular velocity, positive is pitching up, NaN to be ignored."]
13234 pub angular_velocity_y: f32,
13235 #[doc = "Z component of angular velocity, positive is yawing to the right, NaN to be ignored."]
13236 pub angular_velocity_z: f32,
13237 #[doc = "System ID"]
13238 pub target_system: u8,
13239 #[doc = "Component ID"]
13240 pub target_component: u8,
13241 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
13242 pub gimbal_device_id: u8,
13243}
13244impl GIMBAL_MANAGER_SET_ATTITUDE_DATA {
13245 pub const ENCODED_LEN: usize = 35usize;
13246 pub const DEFAULT: Self = Self {
13247 flags: GimbalManagerFlags::DEFAULT,
13248 q: [0.0_f32; 4usize],
13249 angular_velocity_x: 0.0_f32,
13250 angular_velocity_y: 0.0_f32,
13251 angular_velocity_z: 0.0_f32,
13252 target_system: 0_u8,
13253 target_component: 0_u8,
13254 gimbal_device_id: 0_u8,
13255 };
13256 #[cfg(feature = "arbitrary")]
13257 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13258 use arbitrary::{Arbitrary, Unstructured};
13259 let mut buf = [0u8; 1024];
13260 rng.fill_bytes(&mut buf);
13261 let mut unstructured = Unstructured::new(&buf);
13262 Self::arbitrary(&mut unstructured).unwrap_or_default()
13263 }
13264}
13265impl Default for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
13266 fn default() -> Self {
13267 Self::DEFAULT.clone()
13268 }
13269}
13270impl MessageData for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
13271 type Message = MavMessage;
13272 const ID: u32 = 282u32;
13273 const NAME: &'static str = "GIMBAL_MANAGER_SET_ATTITUDE";
13274 const EXTRA_CRC: u8 = 123u8;
13275 const ENCODED_LEN: usize = 35usize;
13276 fn deser(
13277 _version: MavlinkVersion,
13278 __input: &[u8],
13279 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13280 let avail_len = __input.len();
13281 let mut payload_buf = [0; Self::ENCODED_LEN];
13282 let mut buf = if avail_len < Self::ENCODED_LEN {
13283 payload_buf[0..avail_len].copy_from_slice(__input);
13284 Bytes::new(&payload_buf)
13285 } else {
13286 Bytes::new(__input)
13287 };
13288 let mut __struct = Self::default();
13289 let tmp = buf.get_u32_le();
13290 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
13291 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
13292 flag_type: "GimbalManagerFlags",
13293 value: tmp as u32,
13294 })?;
13295 for v in &mut __struct.q {
13296 let val = buf.get_f32_le();
13297 *v = val;
13298 }
13299 __struct.angular_velocity_x = buf.get_f32_le();
13300 __struct.angular_velocity_y = buf.get_f32_le();
13301 __struct.angular_velocity_z = buf.get_f32_le();
13302 __struct.target_system = buf.get_u8();
13303 __struct.target_component = buf.get_u8();
13304 __struct.gimbal_device_id = buf.get_u8();
13305 Ok(__struct)
13306 }
13307 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13308 let mut __tmp = BytesMut::new(bytes);
13309 #[allow(clippy::absurd_extreme_comparisons)]
13310 #[allow(unused_comparisons)]
13311 if __tmp.remaining() < Self::ENCODED_LEN {
13312 panic!(
13313 "buffer is too small (need {} bytes, but got {})",
13314 Self::ENCODED_LEN,
13315 __tmp.remaining(),
13316 )
13317 }
13318 __tmp.put_u32_le(self.flags.bits());
13319 for val in &self.q {
13320 __tmp.put_f32_le(*val);
13321 }
13322 __tmp.put_f32_le(self.angular_velocity_x);
13323 __tmp.put_f32_le(self.angular_velocity_y);
13324 __tmp.put_f32_le(self.angular_velocity_z);
13325 __tmp.put_u8(self.target_system);
13326 __tmp.put_u8(self.target_component);
13327 __tmp.put_u8(self.gimbal_device_id);
13328 if matches!(version, MavlinkVersion::V2) {
13329 let len = __tmp.len();
13330 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13331 } else {
13332 __tmp.len()
13333 }
13334 }
13335}
13336#[doc = "id: 142"]
13337#[doc = "The autopilot is requesting a resource (file, binary, other type of data)."]
13338#[derive(Debug, Clone, PartialEq)]
13339#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13340#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13341pub struct RESOURCE_REQUEST_DATA {
13342 #[doc = "Request ID. This ID should be re-used when sending back URI contents"]
13343 pub request_id: u8,
13344 #[doc = "The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary"]
13345 pub uri_type: u8,
13346 #[doc = "The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)"]
13347 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13348 pub uri: [u8; 120],
13349 #[doc = "The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream."]
13350 pub transfer_type: u8,
13351 #[doc = "The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP)."]
13352 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13353 pub storage: [u8; 120],
13354}
13355impl RESOURCE_REQUEST_DATA {
13356 pub const ENCODED_LEN: usize = 243usize;
13357 pub const DEFAULT: Self = Self {
13358 request_id: 0_u8,
13359 uri_type: 0_u8,
13360 uri: [0_u8; 120usize],
13361 transfer_type: 0_u8,
13362 storage: [0_u8; 120usize],
13363 };
13364 #[cfg(feature = "arbitrary")]
13365 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13366 use arbitrary::{Arbitrary, Unstructured};
13367 let mut buf = [0u8; 1024];
13368 rng.fill_bytes(&mut buf);
13369 let mut unstructured = Unstructured::new(&buf);
13370 Self::arbitrary(&mut unstructured).unwrap_or_default()
13371 }
13372}
13373impl Default for RESOURCE_REQUEST_DATA {
13374 fn default() -> Self {
13375 Self::DEFAULT.clone()
13376 }
13377}
13378impl MessageData for RESOURCE_REQUEST_DATA {
13379 type Message = MavMessage;
13380 const ID: u32 = 142u32;
13381 const NAME: &'static str = "RESOURCE_REQUEST";
13382 const EXTRA_CRC: u8 = 72u8;
13383 const ENCODED_LEN: usize = 243usize;
13384 fn deser(
13385 _version: MavlinkVersion,
13386 __input: &[u8],
13387 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13388 let avail_len = __input.len();
13389 let mut payload_buf = [0; Self::ENCODED_LEN];
13390 let mut buf = if avail_len < Self::ENCODED_LEN {
13391 payload_buf[0..avail_len].copy_from_slice(__input);
13392 Bytes::new(&payload_buf)
13393 } else {
13394 Bytes::new(__input)
13395 };
13396 let mut __struct = Self::default();
13397 __struct.request_id = buf.get_u8();
13398 __struct.uri_type = buf.get_u8();
13399 for v in &mut __struct.uri {
13400 let val = buf.get_u8();
13401 *v = val;
13402 }
13403 __struct.transfer_type = buf.get_u8();
13404 for v in &mut __struct.storage {
13405 let val = buf.get_u8();
13406 *v = val;
13407 }
13408 Ok(__struct)
13409 }
13410 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13411 let mut __tmp = BytesMut::new(bytes);
13412 #[allow(clippy::absurd_extreme_comparisons)]
13413 #[allow(unused_comparisons)]
13414 if __tmp.remaining() < Self::ENCODED_LEN {
13415 panic!(
13416 "buffer is too small (need {} bytes, but got {})",
13417 Self::ENCODED_LEN,
13418 __tmp.remaining(),
13419 )
13420 }
13421 __tmp.put_u8(self.request_id);
13422 __tmp.put_u8(self.uri_type);
13423 for val in &self.uri {
13424 __tmp.put_u8(*val);
13425 }
13426 __tmp.put_u8(self.transfer_type);
13427 for val in &self.storage {
13428 __tmp.put_u8(*val);
13429 }
13430 if matches!(version, MavlinkVersion::V2) {
13431 let len = __tmp.len();
13432 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13433 } else {
13434 __tmp.len()
13435 }
13436 }
13437}
13438#[doc = "id: 45"]
13439#[doc = "Delete all mission items at once."]
13440#[derive(Debug, Clone, PartialEq)]
13441#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13442#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13443pub struct MISSION_CLEAR_ALL_DATA {
13444 #[doc = "System ID"]
13445 pub target_system: u8,
13446 #[doc = "Component ID"]
13447 pub target_component: u8,
13448 #[doc = "Mission type."]
13449 #[cfg_attr(feature = "serde", serde(default))]
13450 pub mission_type: MavMissionType,
13451}
13452impl MISSION_CLEAR_ALL_DATA {
13453 pub const ENCODED_LEN: usize = 3usize;
13454 pub const DEFAULT: Self = Self {
13455 target_system: 0_u8,
13456 target_component: 0_u8,
13457 mission_type: MavMissionType::DEFAULT,
13458 };
13459 #[cfg(feature = "arbitrary")]
13460 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13461 use arbitrary::{Arbitrary, Unstructured};
13462 let mut buf = [0u8; 1024];
13463 rng.fill_bytes(&mut buf);
13464 let mut unstructured = Unstructured::new(&buf);
13465 Self::arbitrary(&mut unstructured).unwrap_or_default()
13466 }
13467}
13468impl Default for MISSION_CLEAR_ALL_DATA {
13469 fn default() -> Self {
13470 Self::DEFAULT.clone()
13471 }
13472}
13473impl MessageData for MISSION_CLEAR_ALL_DATA {
13474 type Message = MavMessage;
13475 const ID: u32 = 45u32;
13476 const NAME: &'static str = "MISSION_CLEAR_ALL";
13477 const EXTRA_CRC: u8 = 232u8;
13478 const ENCODED_LEN: usize = 3usize;
13479 fn deser(
13480 _version: MavlinkVersion,
13481 __input: &[u8],
13482 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13483 let avail_len = __input.len();
13484 let mut payload_buf = [0; Self::ENCODED_LEN];
13485 let mut buf = if avail_len < Self::ENCODED_LEN {
13486 payload_buf[0..avail_len].copy_from_slice(__input);
13487 Bytes::new(&payload_buf)
13488 } else {
13489 Bytes::new(__input)
13490 };
13491 let mut __struct = Self::default();
13492 __struct.target_system = buf.get_u8();
13493 __struct.target_component = buf.get_u8();
13494 let tmp = buf.get_u8();
13495 __struct.mission_type =
13496 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13497 enum_type: "MavMissionType",
13498 value: tmp as u32,
13499 })?;
13500 Ok(__struct)
13501 }
13502 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13503 let mut __tmp = BytesMut::new(bytes);
13504 #[allow(clippy::absurd_extreme_comparisons)]
13505 #[allow(unused_comparisons)]
13506 if __tmp.remaining() < Self::ENCODED_LEN {
13507 panic!(
13508 "buffer is too small (need {} bytes, but got {})",
13509 Self::ENCODED_LEN,
13510 __tmp.remaining(),
13511 )
13512 }
13513 __tmp.put_u8(self.target_system);
13514 __tmp.put_u8(self.target_component);
13515 __tmp.put_u8(self.mission_type as u8);
13516 if matches!(version, MavlinkVersion::V2) {
13517 let len = __tmp.len();
13518 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13519 } else {
13520 __tmp.len()
13521 }
13522 }
13523}
13524#[doc = "id: 23"]
13525#[doc = "Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
13526#[derive(Debug, Clone, PartialEq)]
13527#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13528#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13529pub struct PARAM_SET_DATA {
13530 #[doc = "Onboard parameter value"]
13531 pub param_value: f32,
13532 #[doc = "System ID"]
13533 pub target_system: u8,
13534 #[doc = "Component ID"]
13535 pub target_component: u8,
13536 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
13537 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13538 pub param_id: [u8; 16],
13539 #[doc = "Onboard parameter type."]
13540 pub param_type: MavParamType,
13541}
13542impl PARAM_SET_DATA {
13543 pub const ENCODED_LEN: usize = 23usize;
13544 pub const DEFAULT: Self = Self {
13545 param_value: 0.0_f32,
13546 target_system: 0_u8,
13547 target_component: 0_u8,
13548 param_id: [0_u8; 16usize],
13549 param_type: MavParamType::DEFAULT,
13550 };
13551 #[cfg(feature = "arbitrary")]
13552 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13553 use arbitrary::{Arbitrary, Unstructured};
13554 let mut buf = [0u8; 1024];
13555 rng.fill_bytes(&mut buf);
13556 let mut unstructured = Unstructured::new(&buf);
13557 Self::arbitrary(&mut unstructured).unwrap_or_default()
13558 }
13559}
13560impl Default for PARAM_SET_DATA {
13561 fn default() -> Self {
13562 Self::DEFAULT.clone()
13563 }
13564}
13565impl MessageData for PARAM_SET_DATA {
13566 type Message = MavMessage;
13567 const ID: u32 = 23u32;
13568 const NAME: &'static str = "PARAM_SET";
13569 const EXTRA_CRC: u8 = 168u8;
13570 const ENCODED_LEN: usize = 23usize;
13571 fn deser(
13572 _version: MavlinkVersion,
13573 __input: &[u8],
13574 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13575 let avail_len = __input.len();
13576 let mut payload_buf = [0; Self::ENCODED_LEN];
13577 let mut buf = if avail_len < Self::ENCODED_LEN {
13578 payload_buf[0..avail_len].copy_from_slice(__input);
13579 Bytes::new(&payload_buf)
13580 } else {
13581 Bytes::new(__input)
13582 };
13583 let mut __struct = Self::default();
13584 __struct.param_value = buf.get_f32_le();
13585 __struct.target_system = buf.get_u8();
13586 __struct.target_component = buf.get_u8();
13587 for v in &mut __struct.param_id {
13588 let val = buf.get_u8();
13589 *v = val;
13590 }
13591 let tmp = buf.get_u8();
13592 __struct.param_type =
13593 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13594 enum_type: "MavParamType",
13595 value: tmp as u32,
13596 })?;
13597 Ok(__struct)
13598 }
13599 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13600 let mut __tmp = BytesMut::new(bytes);
13601 #[allow(clippy::absurd_extreme_comparisons)]
13602 #[allow(unused_comparisons)]
13603 if __tmp.remaining() < Self::ENCODED_LEN {
13604 panic!(
13605 "buffer is too small (need {} bytes, but got {})",
13606 Self::ENCODED_LEN,
13607 __tmp.remaining(),
13608 )
13609 }
13610 __tmp.put_f32_le(self.param_value);
13611 __tmp.put_u8(self.target_system);
13612 __tmp.put_u8(self.target_component);
13613 for val in &self.param_id {
13614 __tmp.put_u8(*val);
13615 }
13616 __tmp.put_u8(self.param_type as u8);
13617 if matches!(version, MavlinkVersion::V2) {
13618 let len = __tmp.len();
13619 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13620 } else {
13621 __tmp.len()
13622 }
13623 }
13624}
13625#[doc = "id: 119"]
13626#[doc = "Request a chunk of a log."]
13627#[derive(Debug, Clone, PartialEq)]
13628#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13629#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13630pub struct LOG_REQUEST_DATA_DATA {
13631 #[doc = "Offset into the log"]
13632 pub ofs: u32,
13633 #[doc = "Number of bytes"]
13634 pub count: u32,
13635 #[doc = "Log id (from LOG_ENTRY reply)"]
13636 pub id: u16,
13637 #[doc = "System ID"]
13638 pub target_system: u8,
13639 #[doc = "Component ID"]
13640 pub target_component: u8,
13641}
13642impl LOG_REQUEST_DATA_DATA {
13643 pub const ENCODED_LEN: usize = 12usize;
13644 pub const DEFAULT: Self = Self {
13645 ofs: 0_u32,
13646 count: 0_u32,
13647 id: 0_u16,
13648 target_system: 0_u8,
13649 target_component: 0_u8,
13650 };
13651 #[cfg(feature = "arbitrary")]
13652 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13653 use arbitrary::{Arbitrary, Unstructured};
13654 let mut buf = [0u8; 1024];
13655 rng.fill_bytes(&mut buf);
13656 let mut unstructured = Unstructured::new(&buf);
13657 Self::arbitrary(&mut unstructured).unwrap_or_default()
13658 }
13659}
13660impl Default for LOG_REQUEST_DATA_DATA {
13661 fn default() -> Self {
13662 Self::DEFAULT.clone()
13663 }
13664}
13665impl MessageData for LOG_REQUEST_DATA_DATA {
13666 type Message = MavMessage;
13667 const ID: u32 = 119u32;
13668 const NAME: &'static str = "LOG_REQUEST_DATA";
13669 const EXTRA_CRC: u8 = 116u8;
13670 const ENCODED_LEN: usize = 12usize;
13671 fn deser(
13672 _version: MavlinkVersion,
13673 __input: &[u8],
13674 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13675 let avail_len = __input.len();
13676 let mut payload_buf = [0; Self::ENCODED_LEN];
13677 let mut buf = if avail_len < Self::ENCODED_LEN {
13678 payload_buf[0..avail_len].copy_from_slice(__input);
13679 Bytes::new(&payload_buf)
13680 } else {
13681 Bytes::new(__input)
13682 };
13683 let mut __struct = Self::default();
13684 __struct.ofs = buf.get_u32_le();
13685 __struct.count = buf.get_u32_le();
13686 __struct.id = buf.get_u16_le();
13687 __struct.target_system = buf.get_u8();
13688 __struct.target_component = buf.get_u8();
13689 Ok(__struct)
13690 }
13691 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13692 let mut __tmp = BytesMut::new(bytes);
13693 #[allow(clippy::absurd_extreme_comparisons)]
13694 #[allow(unused_comparisons)]
13695 if __tmp.remaining() < Self::ENCODED_LEN {
13696 panic!(
13697 "buffer is too small (need {} bytes, but got {})",
13698 Self::ENCODED_LEN,
13699 __tmp.remaining(),
13700 )
13701 }
13702 __tmp.put_u32_le(self.ofs);
13703 __tmp.put_u32_le(self.count);
13704 __tmp.put_u16_le(self.id);
13705 __tmp.put_u8(self.target_system);
13706 __tmp.put_u8(self.target_component);
13707 if matches!(version, MavlinkVersion::V2) {
13708 let len = __tmp.len();
13709 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13710 } else {
13711 __tmp.len()
13712 }
13713 }
13714}
13715#[doc = "id: 277"]
13716#[doc = "Camera absolute thermal range. This can be streamed when the associated VIDEO_STREAM_STATUS `flag` field bit VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras)."]
13717#[derive(Debug, Clone, PartialEq)]
13718#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13719#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13720pub struct CAMERA_THERMAL_RANGE_DATA {
13721 #[doc = "Timestamp (time since system boot)."]
13722 pub time_boot_ms: u32,
13723 #[doc = "Temperature max."]
13724 pub max: f32,
13725 #[doc = "Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
13726 pub max_point_x: f32,
13727 #[doc = "Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
13728 pub max_point_y: f32,
13729 #[doc = "Temperature min."]
13730 pub min: f32,
13731 #[doc = "Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
13732 pub min_point_x: f32,
13733 #[doc = "Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
13734 pub min_point_y: f32,
13735 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
13736 pub stream_id: u8,
13737 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
13738 pub camera_device_id: u8,
13739}
13740impl CAMERA_THERMAL_RANGE_DATA {
13741 pub const ENCODED_LEN: usize = 30usize;
13742 pub const DEFAULT: Self = Self {
13743 time_boot_ms: 0_u32,
13744 max: 0.0_f32,
13745 max_point_x: 0.0_f32,
13746 max_point_y: 0.0_f32,
13747 min: 0.0_f32,
13748 min_point_x: 0.0_f32,
13749 min_point_y: 0.0_f32,
13750 stream_id: 0_u8,
13751 camera_device_id: 0_u8,
13752 };
13753 #[cfg(feature = "arbitrary")]
13754 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13755 use arbitrary::{Arbitrary, Unstructured};
13756 let mut buf = [0u8; 1024];
13757 rng.fill_bytes(&mut buf);
13758 let mut unstructured = Unstructured::new(&buf);
13759 Self::arbitrary(&mut unstructured).unwrap_or_default()
13760 }
13761}
13762impl Default for CAMERA_THERMAL_RANGE_DATA {
13763 fn default() -> Self {
13764 Self::DEFAULT.clone()
13765 }
13766}
13767impl MessageData for CAMERA_THERMAL_RANGE_DATA {
13768 type Message = MavMessage;
13769 const ID: u32 = 277u32;
13770 const NAME: &'static str = "CAMERA_THERMAL_RANGE";
13771 const EXTRA_CRC: u8 = 62u8;
13772 const ENCODED_LEN: usize = 30usize;
13773 fn deser(
13774 _version: MavlinkVersion,
13775 __input: &[u8],
13776 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13777 let avail_len = __input.len();
13778 let mut payload_buf = [0; Self::ENCODED_LEN];
13779 let mut buf = if avail_len < Self::ENCODED_LEN {
13780 payload_buf[0..avail_len].copy_from_slice(__input);
13781 Bytes::new(&payload_buf)
13782 } else {
13783 Bytes::new(__input)
13784 };
13785 let mut __struct = Self::default();
13786 __struct.time_boot_ms = buf.get_u32_le();
13787 __struct.max = buf.get_f32_le();
13788 __struct.max_point_x = buf.get_f32_le();
13789 __struct.max_point_y = buf.get_f32_le();
13790 __struct.min = buf.get_f32_le();
13791 __struct.min_point_x = buf.get_f32_le();
13792 __struct.min_point_y = buf.get_f32_le();
13793 __struct.stream_id = buf.get_u8();
13794 __struct.camera_device_id = buf.get_u8();
13795 Ok(__struct)
13796 }
13797 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13798 let mut __tmp = BytesMut::new(bytes);
13799 #[allow(clippy::absurd_extreme_comparisons)]
13800 #[allow(unused_comparisons)]
13801 if __tmp.remaining() < Self::ENCODED_LEN {
13802 panic!(
13803 "buffer is too small (need {} bytes, but got {})",
13804 Self::ENCODED_LEN,
13805 __tmp.remaining(),
13806 )
13807 }
13808 __tmp.put_u32_le(self.time_boot_ms);
13809 __tmp.put_f32_le(self.max);
13810 __tmp.put_f32_le(self.max_point_x);
13811 __tmp.put_f32_le(self.max_point_y);
13812 __tmp.put_f32_le(self.min);
13813 __tmp.put_f32_le(self.min_point_x);
13814 __tmp.put_f32_le(self.min_point_y);
13815 __tmp.put_u8(self.stream_id);
13816 __tmp.put_u8(self.camera_device_id);
13817 if matches!(version, MavlinkVersion::V2) {
13818 let len = __tmp.len();
13819 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13820 } else {
13821 __tmp.len()
13822 }
13823 }
13824}
13825#[doc = "id: 413"]
13826#[doc = "Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore)."]
13827#[derive(Debug, Clone, PartialEq)]
13828#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13829#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13830pub struct RESPONSE_EVENT_ERROR_DATA {
13831 #[doc = "Sequence number."]
13832 pub sequence: u16,
13833 #[doc = "Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT."]
13834 pub sequence_oldest_available: u16,
13835 #[doc = "System ID"]
13836 pub target_system: u8,
13837 #[doc = "Component ID"]
13838 pub target_component: u8,
13839 #[doc = "Error reason."]
13840 pub reason: MavEventErrorReason,
13841}
13842impl RESPONSE_EVENT_ERROR_DATA {
13843 pub const ENCODED_LEN: usize = 7usize;
13844 pub const DEFAULT: Self = Self {
13845 sequence: 0_u16,
13846 sequence_oldest_available: 0_u16,
13847 target_system: 0_u8,
13848 target_component: 0_u8,
13849 reason: MavEventErrorReason::DEFAULT,
13850 };
13851 #[cfg(feature = "arbitrary")]
13852 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13853 use arbitrary::{Arbitrary, Unstructured};
13854 let mut buf = [0u8; 1024];
13855 rng.fill_bytes(&mut buf);
13856 let mut unstructured = Unstructured::new(&buf);
13857 Self::arbitrary(&mut unstructured).unwrap_or_default()
13858 }
13859}
13860impl Default for RESPONSE_EVENT_ERROR_DATA {
13861 fn default() -> Self {
13862 Self::DEFAULT.clone()
13863 }
13864}
13865impl MessageData for RESPONSE_EVENT_ERROR_DATA {
13866 type Message = MavMessage;
13867 const ID: u32 = 413u32;
13868 const NAME: &'static str = "RESPONSE_EVENT_ERROR";
13869 const EXTRA_CRC: u8 = 77u8;
13870 const ENCODED_LEN: usize = 7usize;
13871 fn deser(
13872 _version: MavlinkVersion,
13873 __input: &[u8],
13874 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13875 let avail_len = __input.len();
13876 let mut payload_buf = [0; Self::ENCODED_LEN];
13877 let mut buf = if avail_len < Self::ENCODED_LEN {
13878 payload_buf[0..avail_len].copy_from_slice(__input);
13879 Bytes::new(&payload_buf)
13880 } else {
13881 Bytes::new(__input)
13882 };
13883 let mut __struct = Self::default();
13884 __struct.sequence = buf.get_u16_le();
13885 __struct.sequence_oldest_available = buf.get_u16_le();
13886 __struct.target_system = buf.get_u8();
13887 __struct.target_component = buf.get_u8();
13888 let tmp = buf.get_u8();
13889 __struct.reason =
13890 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13891 enum_type: "MavEventErrorReason",
13892 value: tmp as u32,
13893 })?;
13894 Ok(__struct)
13895 }
13896 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13897 let mut __tmp = BytesMut::new(bytes);
13898 #[allow(clippy::absurd_extreme_comparisons)]
13899 #[allow(unused_comparisons)]
13900 if __tmp.remaining() < Self::ENCODED_LEN {
13901 panic!(
13902 "buffer is too small (need {} bytes, but got {})",
13903 Self::ENCODED_LEN,
13904 __tmp.remaining(),
13905 )
13906 }
13907 __tmp.put_u16_le(self.sequence);
13908 __tmp.put_u16_le(self.sequence_oldest_available);
13909 __tmp.put_u8(self.target_system);
13910 __tmp.put_u8(self.target_component);
13911 __tmp.put_u8(self.reason as u8);
13912 if matches!(version, MavlinkVersion::V2) {
13913 let len = __tmp.len();
13914 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13915 } else {
13916 __tmp.len()
13917 }
13918 }
13919}
13920#[doc = "id: 129"]
13921#[doc = "The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units."]
13922#[derive(Debug, Clone, PartialEq)]
13923#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13924#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13925pub struct SCALED_IMU3_DATA {
13926 #[doc = "Timestamp (time since system boot)."]
13927 pub time_boot_ms: u32,
13928 #[doc = "X acceleration"]
13929 pub xacc: i16,
13930 #[doc = "Y acceleration"]
13931 pub yacc: i16,
13932 #[doc = "Z acceleration"]
13933 pub zacc: i16,
13934 #[doc = "Angular speed around X axis"]
13935 pub xgyro: i16,
13936 #[doc = "Angular speed around Y axis"]
13937 pub ygyro: i16,
13938 #[doc = "Angular speed around Z axis"]
13939 pub zgyro: i16,
13940 #[doc = "X Magnetic field"]
13941 pub xmag: i16,
13942 #[doc = "Y Magnetic field"]
13943 pub ymag: i16,
13944 #[doc = "Z Magnetic field"]
13945 pub zmag: i16,
13946 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
13947 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13948 pub temperature: i16,
13949}
13950impl SCALED_IMU3_DATA {
13951 pub const ENCODED_LEN: usize = 24usize;
13952 pub const DEFAULT: Self = Self {
13953 time_boot_ms: 0_u32,
13954 xacc: 0_i16,
13955 yacc: 0_i16,
13956 zacc: 0_i16,
13957 xgyro: 0_i16,
13958 ygyro: 0_i16,
13959 zgyro: 0_i16,
13960 xmag: 0_i16,
13961 ymag: 0_i16,
13962 zmag: 0_i16,
13963 temperature: 0_i16,
13964 };
13965 #[cfg(feature = "arbitrary")]
13966 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13967 use arbitrary::{Arbitrary, Unstructured};
13968 let mut buf = [0u8; 1024];
13969 rng.fill_bytes(&mut buf);
13970 let mut unstructured = Unstructured::new(&buf);
13971 Self::arbitrary(&mut unstructured).unwrap_or_default()
13972 }
13973}
13974impl Default for SCALED_IMU3_DATA {
13975 fn default() -> Self {
13976 Self::DEFAULT.clone()
13977 }
13978}
13979impl MessageData for SCALED_IMU3_DATA {
13980 type Message = MavMessage;
13981 const ID: u32 = 129u32;
13982 const NAME: &'static str = "SCALED_IMU3";
13983 const EXTRA_CRC: u8 = 46u8;
13984 const ENCODED_LEN: usize = 24usize;
13985 fn deser(
13986 _version: MavlinkVersion,
13987 __input: &[u8],
13988 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13989 let avail_len = __input.len();
13990 let mut payload_buf = [0; Self::ENCODED_LEN];
13991 let mut buf = if avail_len < Self::ENCODED_LEN {
13992 payload_buf[0..avail_len].copy_from_slice(__input);
13993 Bytes::new(&payload_buf)
13994 } else {
13995 Bytes::new(__input)
13996 };
13997 let mut __struct = Self::default();
13998 __struct.time_boot_ms = buf.get_u32_le();
13999 __struct.xacc = buf.get_i16_le();
14000 __struct.yacc = buf.get_i16_le();
14001 __struct.zacc = buf.get_i16_le();
14002 __struct.xgyro = buf.get_i16_le();
14003 __struct.ygyro = buf.get_i16_le();
14004 __struct.zgyro = buf.get_i16_le();
14005 __struct.xmag = buf.get_i16_le();
14006 __struct.ymag = buf.get_i16_le();
14007 __struct.zmag = buf.get_i16_le();
14008 __struct.temperature = buf.get_i16_le();
14009 Ok(__struct)
14010 }
14011 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14012 let mut __tmp = BytesMut::new(bytes);
14013 #[allow(clippy::absurd_extreme_comparisons)]
14014 #[allow(unused_comparisons)]
14015 if __tmp.remaining() < Self::ENCODED_LEN {
14016 panic!(
14017 "buffer is too small (need {} bytes, but got {})",
14018 Self::ENCODED_LEN,
14019 __tmp.remaining(),
14020 )
14021 }
14022 __tmp.put_u32_le(self.time_boot_ms);
14023 __tmp.put_i16_le(self.xacc);
14024 __tmp.put_i16_le(self.yacc);
14025 __tmp.put_i16_le(self.zacc);
14026 __tmp.put_i16_le(self.xgyro);
14027 __tmp.put_i16_le(self.ygyro);
14028 __tmp.put_i16_le(self.zgyro);
14029 __tmp.put_i16_le(self.xmag);
14030 __tmp.put_i16_le(self.ymag);
14031 __tmp.put_i16_le(self.zmag);
14032 __tmp.put_i16_le(self.temperature);
14033 if matches!(version, MavlinkVersion::V2) {
14034 let len = __tmp.len();
14035 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14036 } else {
14037 __tmp.len()
14038 }
14039 }
14040}
14041#[doc = "id: 262"]
14042#[doc = "Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
14043#[derive(Debug, Clone, PartialEq)]
14044#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14045#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14046pub struct CAMERA_CAPTURE_STATUS_DATA {
14047 #[doc = "Timestamp (time since system boot)."]
14048 pub time_boot_ms: u32,
14049 #[doc = "Image capture interval"]
14050 pub image_interval: f32,
14051 #[doc = "Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy."]
14052 pub recording_time_ms: u32,
14053 #[doc = "Available storage capacity."]
14054 pub available_capacity: f32,
14055 #[doc = "Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)"]
14056 pub image_status: u8,
14057 #[doc = "Current status of video capturing (0: idle, 1: capture in progress)"]
14058 pub video_status: u8,
14059 #[doc = "Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT)."]
14060 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14061 pub image_count: i32,
14062 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
14063 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14064 pub camera_device_id: u8,
14065}
14066impl CAMERA_CAPTURE_STATUS_DATA {
14067 pub const ENCODED_LEN: usize = 23usize;
14068 pub const DEFAULT: Self = Self {
14069 time_boot_ms: 0_u32,
14070 image_interval: 0.0_f32,
14071 recording_time_ms: 0_u32,
14072 available_capacity: 0.0_f32,
14073 image_status: 0_u8,
14074 video_status: 0_u8,
14075 image_count: 0_i32,
14076 camera_device_id: 0_u8,
14077 };
14078 #[cfg(feature = "arbitrary")]
14079 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14080 use arbitrary::{Arbitrary, Unstructured};
14081 let mut buf = [0u8; 1024];
14082 rng.fill_bytes(&mut buf);
14083 let mut unstructured = Unstructured::new(&buf);
14084 Self::arbitrary(&mut unstructured).unwrap_or_default()
14085 }
14086}
14087impl Default for CAMERA_CAPTURE_STATUS_DATA {
14088 fn default() -> Self {
14089 Self::DEFAULT.clone()
14090 }
14091}
14092impl MessageData for CAMERA_CAPTURE_STATUS_DATA {
14093 type Message = MavMessage;
14094 const ID: u32 = 262u32;
14095 const NAME: &'static str = "CAMERA_CAPTURE_STATUS";
14096 const EXTRA_CRC: u8 = 12u8;
14097 const ENCODED_LEN: usize = 23usize;
14098 fn deser(
14099 _version: MavlinkVersion,
14100 __input: &[u8],
14101 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14102 let avail_len = __input.len();
14103 let mut payload_buf = [0; Self::ENCODED_LEN];
14104 let mut buf = if avail_len < Self::ENCODED_LEN {
14105 payload_buf[0..avail_len].copy_from_slice(__input);
14106 Bytes::new(&payload_buf)
14107 } else {
14108 Bytes::new(__input)
14109 };
14110 let mut __struct = Self::default();
14111 __struct.time_boot_ms = buf.get_u32_le();
14112 __struct.image_interval = buf.get_f32_le();
14113 __struct.recording_time_ms = buf.get_u32_le();
14114 __struct.available_capacity = buf.get_f32_le();
14115 __struct.image_status = buf.get_u8();
14116 __struct.video_status = buf.get_u8();
14117 __struct.image_count = buf.get_i32_le();
14118 __struct.camera_device_id = buf.get_u8();
14119 Ok(__struct)
14120 }
14121 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14122 let mut __tmp = BytesMut::new(bytes);
14123 #[allow(clippy::absurd_extreme_comparisons)]
14124 #[allow(unused_comparisons)]
14125 if __tmp.remaining() < Self::ENCODED_LEN {
14126 panic!(
14127 "buffer is too small (need {} bytes, but got {})",
14128 Self::ENCODED_LEN,
14129 __tmp.remaining(),
14130 )
14131 }
14132 __tmp.put_u32_le(self.time_boot_ms);
14133 __tmp.put_f32_le(self.image_interval);
14134 __tmp.put_u32_le(self.recording_time_ms);
14135 __tmp.put_f32_le(self.available_capacity);
14136 __tmp.put_u8(self.image_status);
14137 __tmp.put_u8(self.video_status);
14138 __tmp.put_i32_le(self.image_count);
14139 __tmp.put_u8(self.camera_device_id);
14140 if matches!(version, MavlinkVersion::V2) {
14141 let len = __tmp.len();
14142 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14143 } else {
14144 __tmp.len()
14145 }
14146 }
14147}
14148#[doc = "id: 323"]
14149#[doc = "Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response."]
14150#[derive(Debug, Clone, PartialEq)]
14151#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14152#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14153pub struct PARAM_EXT_SET_DATA {
14154 #[doc = "System ID"]
14155 pub target_system: u8,
14156 #[doc = "Component ID"]
14157 pub target_component: u8,
14158 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
14159 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14160 pub param_id: [u8; 16],
14161 #[doc = "Parameter value"]
14162 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14163 pub param_value: [u8; 128],
14164 #[doc = "Parameter type."]
14165 pub param_type: MavParamExtType,
14166}
14167impl PARAM_EXT_SET_DATA {
14168 pub const ENCODED_LEN: usize = 147usize;
14169 pub const DEFAULT: Self = Self {
14170 target_system: 0_u8,
14171 target_component: 0_u8,
14172 param_id: [0_u8; 16usize],
14173 param_value: [0_u8; 128usize],
14174 param_type: MavParamExtType::DEFAULT,
14175 };
14176 #[cfg(feature = "arbitrary")]
14177 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14178 use arbitrary::{Arbitrary, Unstructured};
14179 let mut buf = [0u8; 1024];
14180 rng.fill_bytes(&mut buf);
14181 let mut unstructured = Unstructured::new(&buf);
14182 Self::arbitrary(&mut unstructured).unwrap_or_default()
14183 }
14184}
14185impl Default for PARAM_EXT_SET_DATA {
14186 fn default() -> Self {
14187 Self::DEFAULT.clone()
14188 }
14189}
14190impl MessageData for PARAM_EXT_SET_DATA {
14191 type Message = MavMessage;
14192 const ID: u32 = 323u32;
14193 const NAME: &'static str = "PARAM_EXT_SET";
14194 const EXTRA_CRC: u8 = 78u8;
14195 const ENCODED_LEN: usize = 147usize;
14196 fn deser(
14197 _version: MavlinkVersion,
14198 __input: &[u8],
14199 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14200 let avail_len = __input.len();
14201 let mut payload_buf = [0; Self::ENCODED_LEN];
14202 let mut buf = if avail_len < Self::ENCODED_LEN {
14203 payload_buf[0..avail_len].copy_from_slice(__input);
14204 Bytes::new(&payload_buf)
14205 } else {
14206 Bytes::new(__input)
14207 };
14208 let mut __struct = Self::default();
14209 __struct.target_system = buf.get_u8();
14210 __struct.target_component = buf.get_u8();
14211 for v in &mut __struct.param_id {
14212 let val = buf.get_u8();
14213 *v = val;
14214 }
14215 for v in &mut __struct.param_value {
14216 let val = buf.get_u8();
14217 *v = val;
14218 }
14219 let tmp = buf.get_u8();
14220 __struct.param_type =
14221 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14222 enum_type: "MavParamExtType",
14223 value: tmp as u32,
14224 })?;
14225 Ok(__struct)
14226 }
14227 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14228 let mut __tmp = BytesMut::new(bytes);
14229 #[allow(clippy::absurd_extreme_comparisons)]
14230 #[allow(unused_comparisons)]
14231 if __tmp.remaining() < Self::ENCODED_LEN {
14232 panic!(
14233 "buffer is too small (need {} bytes, but got {})",
14234 Self::ENCODED_LEN,
14235 __tmp.remaining(),
14236 )
14237 }
14238 __tmp.put_u8(self.target_system);
14239 __tmp.put_u8(self.target_component);
14240 for val in &self.param_id {
14241 __tmp.put_u8(*val);
14242 }
14243 for val in &self.param_value {
14244 __tmp.put_u8(*val);
14245 }
14246 __tmp.put_u8(self.param_type as u8);
14247 if matches!(version, MavlinkVersion::V2) {
14248 let len = __tmp.len();
14249 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14250 } else {
14251 __tmp.len()
14252 }
14253 }
14254}
14255#[doc = "id: 140"]
14256#[doc = "Set the vehicle attitude and body angular rates."]
14257#[derive(Debug, Clone, PartialEq)]
14258#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14259#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14260pub struct ACTUATOR_CONTROL_TARGET_DATA {
14261 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14262 pub time_usec: u64,
14263 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
14264 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14265 pub controls: [f32; 8],
14266 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
14267 pub group_mlx: u8,
14268}
14269impl ACTUATOR_CONTROL_TARGET_DATA {
14270 pub const ENCODED_LEN: usize = 41usize;
14271 pub const DEFAULT: Self = Self {
14272 time_usec: 0_u64,
14273 controls: [0.0_f32; 8usize],
14274 group_mlx: 0_u8,
14275 };
14276 #[cfg(feature = "arbitrary")]
14277 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14278 use arbitrary::{Arbitrary, Unstructured};
14279 let mut buf = [0u8; 1024];
14280 rng.fill_bytes(&mut buf);
14281 let mut unstructured = Unstructured::new(&buf);
14282 Self::arbitrary(&mut unstructured).unwrap_or_default()
14283 }
14284}
14285impl Default for ACTUATOR_CONTROL_TARGET_DATA {
14286 fn default() -> Self {
14287 Self::DEFAULT.clone()
14288 }
14289}
14290impl MessageData for ACTUATOR_CONTROL_TARGET_DATA {
14291 type Message = MavMessage;
14292 const ID: u32 = 140u32;
14293 const NAME: &'static str = "ACTUATOR_CONTROL_TARGET";
14294 const EXTRA_CRC: u8 = 181u8;
14295 const ENCODED_LEN: usize = 41usize;
14296 fn deser(
14297 _version: MavlinkVersion,
14298 __input: &[u8],
14299 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14300 let avail_len = __input.len();
14301 let mut payload_buf = [0; Self::ENCODED_LEN];
14302 let mut buf = if avail_len < Self::ENCODED_LEN {
14303 payload_buf[0..avail_len].copy_from_slice(__input);
14304 Bytes::new(&payload_buf)
14305 } else {
14306 Bytes::new(__input)
14307 };
14308 let mut __struct = Self::default();
14309 __struct.time_usec = buf.get_u64_le();
14310 for v in &mut __struct.controls {
14311 let val = buf.get_f32_le();
14312 *v = val;
14313 }
14314 __struct.group_mlx = buf.get_u8();
14315 Ok(__struct)
14316 }
14317 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14318 let mut __tmp = BytesMut::new(bytes);
14319 #[allow(clippy::absurd_extreme_comparisons)]
14320 #[allow(unused_comparisons)]
14321 if __tmp.remaining() < Self::ENCODED_LEN {
14322 panic!(
14323 "buffer is too small (need {} bytes, but got {})",
14324 Self::ENCODED_LEN,
14325 __tmp.remaining(),
14326 )
14327 }
14328 __tmp.put_u64_le(self.time_usec);
14329 for val in &self.controls {
14330 __tmp.put_f32_le(*val);
14331 }
14332 __tmp.put_u8(self.group_mlx);
14333 if matches!(version, MavlinkVersion::V2) {
14334 let len = __tmp.len();
14335 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14336 } else {
14337 __tmp.len()
14338 }
14339 }
14340}
14341#[doc = "id: 360"]
14342#[doc = "Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT)."]
14343#[derive(Debug, Clone, PartialEq)]
14344#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14345#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14346pub struct ORBIT_EXECUTION_STATUS_DATA {
14347 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14348 pub time_usec: u64,
14349 #[doc = "Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise."]
14350 pub radius: f32,
14351 #[doc = "X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
14352 pub x: i32,
14353 #[doc = "Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
14354 pub y: i32,
14355 #[doc = "Altitude of center point. Coordinate system depends on frame field."]
14356 pub z: f32,
14357 #[doc = "The coordinate system of the fields: x, y, z."]
14358 pub frame: MavFrame,
14359}
14360impl ORBIT_EXECUTION_STATUS_DATA {
14361 pub const ENCODED_LEN: usize = 25usize;
14362 pub const DEFAULT: Self = Self {
14363 time_usec: 0_u64,
14364 radius: 0.0_f32,
14365 x: 0_i32,
14366 y: 0_i32,
14367 z: 0.0_f32,
14368 frame: MavFrame::DEFAULT,
14369 };
14370 #[cfg(feature = "arbitrary")]
14371 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14372 use arbitrary::{Arbitrary, Unstructured};
14373 let mut buf = [0u8; 1024];
14374 rng.fill_bytes(&mut buf);
14375 let mut unstructured = Unstructured::new(&buf);
14376 Self::arbitrary(&mut unstructured).unwrap_or_default()
14377 }
14378}
14379impl Default for ORBIT_EXECUTION_STATUS_DATA {
14380 fn default() -> Self {
14381 Self::DEFAULT.clone()
14382 }
14383}
14384impl MessageData for ORBIT_EXECUTION_STATUS_DATA {
14385 type Message = MavMessage;
14386 const ID: u32 = 360u32;
14387 const NAME: &'static str = "ORBIT_EXECUTION_STATUS";
14388 const EXTRA_CRC: u8 = 11u8;
14389 const ENCODED_LEN: usize = 25usize;
14390 fn deser(
14391 _version: MavlinkVersion,
14392 __input: &[u8],
14393 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14394 let avail_len = __input.len();
14395 let mut payload_buf = [0; Self::ENCODED_LEN];
14396 let mut buf = if avail_len < Self::ENCODED_LEN {
14397 payload_buf[0..avail_len].copy_from_slice(__input);
14398 Bytes::new(&payload_buf)
14399 } else {
14400 Bytes::new(__input)
14401 };
14402 let mut __struct = Self::default();
14403 __struct.time_usec = buf.get_u64_le();
14404 __struct.radius = buf.get_f32_le();
14405 __struct.x = buf.get_i32_le();
14406 __struct.y = buf.get_i32_le();
14407 __struct.z = buf.get_f32_le();
14408 let tmp = buf.get_u8();
14409 __struct.frame =
14410 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14411 enum_type: "MavFrame",
14412 value: tmp as u32,
14413 })?;
14414 Ok(__struct)
14415 }
14416 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14417 let mut __tmp = BytesMut::new(bytes);
14418 #[allow(clippy::absurd_extreme_comparisons)]
14419 #[allow(unused_comparisons)]
14420 if __tmp.remaining() < Self::ENCODED_LEN {
14421 panic!(
14422 "buffer is too small (need {} bytes, but got {})",
14423 Self::ENCODED_LEN,
14424 __tmp.remaining(),
14425 )
14426 }
14427 __tmp.put_u64_le(self.time_usec);
14428 __tmp.put_f32_le(self.radius);
14429 __tmp.put_i32_le(self.x);
14430 __tmp.put_i32_le(self.y);
14431 __tmp.put_f32_le(self.z);
14432 __tmp.put_u8(self.frame as u8);
14433 if matches!(version, MavlinkVersion::V2) {
14434 let len = __tmp.len();
14435 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14436 } else {
14437 __tmp.len()
14438 }
14439 }
14440}
14441#[doc = "id: 105"]
14442#[doc = "The IMU readings in SI units in NED body frame."]
14443#[derive(Debug, Clone, PartialEq)]
14444#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14445#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14446pub struct HIGHRES_IMU_DATA {
14447 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14448 pub time_usec: u64,
14449 #[doc = "X acceleration"]
14450 pub xacc: f32,
14451 #[doc = "Y acceleration"]
14452 pub yacc: f32,
14453 #[doc = "Z acceleration"]
14454 pub zacc: f32,
14455 #[doc = "Angular speed around X axis"]
14456 pub xgyro: f32,
14457 #[doc = "Angular speed around Y axis"]
14458 pub ygyro: f32,
14459 #[doc = "Angular speed around Z axis"]
14460 pub zgyro: f32,
14461 #[doc = "X Magnetic field"]
14462 pub xmag: f32,
14463 #[doc = "Y Magnetic field"]
14464 pub ymag: f32,
14465 #[doc = "Z Magnetic field"]
14466 pub zmag: f32,
14467 #[doc = "Absolute pressure"]
14468 pub abs_pressure: f32,
14469 #[doc = "Differential pressure"]
14470 pub diff_pressure: f32,
14471 #[doc = "Altitude calculated from pressure"]
14472 pub pressure_alt: f32,
14473 #[doc = "Temperature"]
14474 pub temperature: f32,
14475 #[doc = "Bitmap for fields that have updated since last message"]
14476 pub fields_updated: HighresImuUpdatedFlags,
14477 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
14478 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14479 pub id: u8,
14480}
14481impl HIGHRES_IMU_DATA {
14482 pub const ENCODED_LEN: usize = 63usize;
14483 pub const DEFAULT: Self = Self {
14484 time_usec: 0_u64,
14485 xacc: 0.0_f32,
14486 yacc: 0.0_f32,
14487 zacc: 0.0_f32,
14488 xgyro: 0.0_f32,
14489 ygyro: 0.0_f32,
14490 zgyro: 0.0_f32,
14491 xmag: 0.0_f32,
14492 ymag: 0.0_f32,
14493 zmag: 0.0_f32,
14494 abs_pressure: 0.0_f32,
14495 diff_pressure: 0.0_f32,
14496 pressure_alt: 0.0_f32,
14497 temperature: 0.0_f32,
14498 fields_updated: HighresImuUpdatedFlags::DEFAULT,
14499 id: 0_u8,
14500 };
14501 #[cfg(feature = "arbitrary")]
14502 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14503 use arbitrary::{Arbitrary, Unstructured};
14504 let mut buf = [0u8; 1024];
14505 rng.fill_bytes(&mut buf);
14506 let mut unstructured = Unstructured::new(&buf);
14507 Self::arbitrary(&mut unstructured).unwrap_or_default()
14508 }
14509}
14510impl Default for HIGHRES_IMU_DATA {
14511 fn default() -> Self {
14512 Self::DEFAULT.clone()
14513 }
14514}
14515impl MessageData for HIGHRES_IMU_DATA {
14516 type Message = MavMessage;
14517 const ID: u32 = 105u32;
14518 const NAME: &'static str = "HIGHRES_IMU";
14519 const EXTRA_CRC: u8 = 93u8;
14520 const ENCODED_LEN: usize = 63usize;
14521 fn deser(
14522 _version: MavlinkVersion,
14523 __input: &[u8],
14524 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14525 let avail_len = __input.len();
14526 let mut payload_buf = [0; Self::ENCODED_LEN];
14527 let mut buf = if avail_len < Self::ENCODED_LEN {
14528 payload_buf[0..avail_len].copy_from_slice(__input);
14529 Bytes::new(&payload_buf)
14530 } else {
14531 Bytes::new(__input)
14532 };
14533 let mut __struct = Self::default();
14534 __struct.time_usec = buf.get_u64_le();
14535 __struct.xacc = buf.get_f32_le();
14536 __struct.yacc = buf.get_f32_le();
14537 __struct.zacc = buf.get_f32_le();
14538 __struct.xgyro = buf.get_f32_le();
14539 __struct.ygyro = buf.get_f32_le();
14540 __struct.zgyro = buf.get_f32_le();
14541 __struct.xmag = buf.get_f32_le();
14542 __struct.ymag = buf.get_f32_le();
14543 __struct.zmag = buf.get_f32_le();
14544 __struct.abs_pressure = buf.get_f32_le();
14545 __struct.diff_pressure = buf.get_f32_le();
14546 __struct.pressure_alt = buf.get_f32_le();
14547 __struct.temperature = buf.get_f32_le();
14548 let tmp = buf.get_u16_le();
14549 __struct.fields_updated = HighresImuUpdatedFlags::from_bits(
14550 tmp & HighresImuUpdatedFlags::all().bits(),
14551 )
14552 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14553 flag_type: "HighresImuUpdatedFlags",
14554 value: tmp as u32,
14555 })?;
14556 __struct.id = buf.get_u8();
14557 Ok(__struct)
14558 }
14559 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14560 let mut __tmp = BytesMut::new(bytes);
14561 #[allow(clippy::absurd_extreme_comparisons)]
14562 #[allow(unused_comparisons)]
14563 if __tmp.remaining() < Self::ENCODED_LEN {
14564 panic!(
14565 "buffer is too small (need {} bytes, but got {})",
14566 Self::ENCODED_LEN,
14567 __tmp.remaining(),
14568 )
14569 }
14570 __tmp.put_u64_le(self.time_usec);
14571 __tmp.put_f32_le(self.xacc);
14572 __tmp.put_f32_le(self.yacc);
14573 __tmp.put_f32_le(self.zacc);
14574 __tmp.put_f32_le(self.xgyro);
14575 __tmp.put_f32_le(self.ygyro);
14576 __tmp.put_f32_le(self.zgyro);
14577 __tmp.put_f32_le(self.xmag);
14578 __tmp.put_f32_le(self.ymag);
14579 __tmp.put_f32_le(self.zmag);
14580 __tmp.put_f32_le(self.abs_pressure);
14581 __tmp.put_f32_le(self.diff_pressure);
14582 __tmp.put_f32_le(self.pressure_alt);
14583 __tmp.put_f32_le(self.temperature);
14584 __tmp.put_u16_le(self.fields_updated.bits());
14585 __tmp.put_u8(self.id);
14586 if matches!(version, MavlinkVersion::V2) {
14587 let len = __tmp.len();
14588 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14589 } else {
14590 __tmp.len()
14591 }
14592 }
14593}
14594#[doc = "id: 12904"]
14595#[doc = "Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information."]
14596#[derive(Debug, Clone, PartialEq)]
14597#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14598#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14599pub struct OPEN_DRONE_ID_SYSTEM_DATA {
14600 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
14601 pub operator_latitude: i32,
14602 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
14603 pub operator_longitude: i32,
14604 #[doc = "Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
14605 pub area_ceiling: f32,
14606 #[doc = "Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
14607 pub area_floor: f32,
14608 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
14609 pub operator_altitude_geo: f32,
14610 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
14611 pub timestamp: u32,
14612 #[doc = "Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA."]
14613 pub area_count: u16,
14614 #[doc = "Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA."]
14615 pub area_radius: u16,
14616 #[doc = "System ID (0 for broadcast)."]
14617 pub target_system: u8,
14618 #[doc = "Component ID (0 for broadcast)."]
14619 pub target_component: u8,
14620 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
14621 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14622 pub id_or_mac: [u8; 20],
14623 #[doc = "Specifies the operator location type."]
14624 pub operator_location_type: MavOdidOperatorLocationType,
14625 #[doc = "Specifies the classification type of the UA."]
14626 pub classification_type: MavOdidClassificationType,
14627 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA."]
14628 pub category_eu: MavOdidCategoryEu,
14629 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA."]
14630 pub class_eu: MavOdidClassEu,
14631}
14632impl OPEN_DRONE_ID_SYSTEM_DATA {
14633 pub const ENCODED_LEN: usize = 54usize;
14634 pub const DEFAULT: Self = Self {
14635 operator_latitude: 0_i32,
14636 operator_longitude: 0_i32,
14637 area_ceiling: 0.0_f32,
14638 area_floor: 0.0_f32,
14639 operator_altitude_geo: 0.0_f32,
14640 timestamp: 0_u32,
14641 area_count: 0_u16,
14642 area_radius: 0_u16,
14643 target_system: 0_u8,
14644 target_component: 0_u8,
14645 id_or_mac: [0_u8; 20usize],
14646 operator_location_type: MavOdidOperatorLocationType::DEFAULT,
14647 classification_type: MavOdidClassificationType::DEFAULT,
14648 category_eu: MavOdidCategoryEu::DEFAULT,
14649 class_eu: MavOdidClassEu::DEFAULT,
14650 };
14651 #[cfg(feature = "arbitrary")]
14652 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14653 use arbitrary::{Arbitrary, Unstructured};
14654 let mut buf = [0u8; 1024];
14655 rng.fill_bytes(&mut buf);
14656 let mut unstructured = Unstructured::new(&buf);
14657 Self::arbitrary(&mut unstructured).unwrap_or_default()
14658 }
14659}
14660impl Default for OPEN_DRONE_ID_SYSTEM_DATA {
14661 fn default() -> Self {
14662 Self::DEFAULT.clone()
14663 }
14664}
14665impl MessageData for OPEN_DRONE_ID_SYSTEM_DATA {
14666 type Message = MavMessage;
14667 const ID: u32 = 12904u32;
14668 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM";
14669 const EXTRA_CRC: u8 = 77u8;
14670 const ENCODED_LEN: usize = 54usize;
14671 fn deser(
14672 _version: MavlinkVersion,
14673 __input: &[u8],
14674 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14675 let avail_len = __input.len();
14676 let mut payload_buf = [0; Self::ENCODED_LEN];
14677 let mut buf = if avail_len < Self::ENCODED_LEN {
14678 payload_buf[0..avail_len].copy_from_slice(__input);
14679 Bytes::new(&payload_buf)
14680 } else {
14681 Bytes::new(__input)
14682 };
14683 let mut __struct = Self::default();
14684 __struct.operator_latitude = buf.get_i32_le();
14685 __struct.operator_longitude = buf.get_i32_le();
14686 __struct.area_ceiling = buf.get_f32_le();
14687 __struct.area_floor = buf.get_f32_le();
14688 __struct.operator_altitude_geo = buf.get_f32_le();
14689 __struct.timestamp = buf.get_u32_le();
14690 __struct.area_count = buf.get_u16_le();
14691 __struct.area_radius = buf.get_u16_le();
14692 __struct.target_system = buf.get_u8();
14693 __struct.target_component = buf.get_u8();
14694 for v in &mut __struct.id_or_mac {
14695 let val = buf.get_u8();
14696 *v = val;
14697 }
14698 let tmp = buf.get_u8();
14699 __struct.operator_location_type =
14700 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14701 enum_type: "MavOdidOperatorLocationType",
14702 value: tmp as u32,
14703 })?;
14704 let tmp = buf.get_u8();
14705 __struct.classification_type =
14706 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14707 enum_type: "MavOdidClassificationType",
14708 value: tmp as u32,
14709 })?;
14710 let tmp = buf.get_u8();
14711 __struct.category_eu =
14712 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14713 enum_type: "MavOdidCategoryEu",
14714 value: tmp as u32,
14715 })?;
14716 let tmp = buf.get_u8();
14717 __struct.class_eu =
14718 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14719 enum_type: "MavOdidClassEu",
14720 value: tmp as u32,
14721 })?;
14722 Ok(__struct)
14723 }
14724 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14725 let mut __tmp = BytesMut::new(bytes);
14726 #[allow(clippy::absurd_extreme_comparisons)]
14727 #[allow(unused_comparisons)]
14728 if __tmp.remaining() < Self::ENCODED_LEN {
14729 panic!(
14730 "buffer is too small (need {} bytes, but got {})",
14731 Self::ENCODED_LEN,
14732 __tmp.remaining(),
14733 )
14734 }
14735 __tmp.put_i32_le(self.operator_latitude);
14736 __tmp.put_i32_le(self.operator_longitude);
14737 __tmp.put_f32_le(self.area_ceiling);
14738 __tmp.put_f32_le(self.area_floor);
14739 __tmp.put_f32_le(self.operator_altitude_geo);
14740 __tmp.put_u32_le(self.timestamp);
14741 __tmp.put_u16_le(self.area_count);
14742 __tmp.put_u16_le(self.area_radius);
14743 __tmp.put_u8(self.target_system);
14744 __tmp.put_u8(self.target_component);
14745 for val in &self.id_or_mac {
14746 __tmp.put_u8(*val);
14747 }
14748 __tmp.put_u8(self.operator_location_type as u8);
14749 __tmp.put_u8(self.classification_type as u8);
14750 __tmp.put_u8(self.category_eu as u8);
14751 __tmp.put_u8(self.class_eu as u8);
14752 if matches!(version, MavlinkVersion::V2) {
14753 let len = __tmp.len();
14754 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14755 } else {
14756 __tmp.len()
14757 }
14758 }
14759}
14760#[doc = "id: 47"]
14761#[doc = "Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero)."]
14762#[derive(Debug, Clone, PartialEq)]
14763#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14764#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14765pub struct MISSION_ACK_DATA {
14766 #[doc = "System ID"]
14767 pub target_system: u8,
14768 #[doc = "Component ID"]
14769 pub target_component: u8,
14770 #[doc = "Mission result."]
14771 pub mavtype: MavMissionResult,
14772 #[doc = "Mission type."]
14773 #[cfg_attr(feature = "serde", serde(default))]
14774 pub mission_type: MavMissionType,
14775 #[doc = "Id of new on-vehicle mission, fence, or rally point plan (on upload to vehicle). The id is calculated and returned by a vehicle when a new plan is uploaded by a GCS. The only requirement on the id is that it must change when there is any change to the on-vehicle plan type (there is no requirement that the id be globally unique). 0 on download from the vehicle to the GCS (on download the ID is set in MISSION_COUNT). 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded."]
14776 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14777 pub opaque_id: u32,
14778}
14779impl MISSION_ACK_DATA {
14780 pub const ENCODED_LEN: usize = 8usize;
14781 pub const DEFAULT: Self = Self {
14782 target_system: 0_u8,
14783 target_component: 0_u8,
14784 mavtype: MavMissionResult::DEFAULT,
14785 mission_type: MavMissionType::DEFAULT,
14786 opaque_id: 0_u32,
14787 };
14788 #[cfg(feature = "arbitrary")]
14789 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14790 use arbitrary::{Arbitrary, Unstructured};
14791 let mut buf = [0u8; 1024];
14792 rng.fill_bytes(&mut buf);
14793 let mut unstructured = Unstructured::new(&buf);
14794 Self::arbitrary(&mut unstructured).unwrap_or_default()
14795 }
14796}
14797impl Default for MISSION_ACK_DATA {
14798 fn default() -> Self {
14799 Self::DEFAULT.clone()
14800 }
14801}
14802impl MessageData for MISSION_ACK_DATA {
14803 type Message = MavMessage;
14804 const ID: u32 = 47u32;
14805 const NAME: &'static str = "MISSION_ACK";
14806 const EXTRA_CRC: u8 = 153u8;
14807 const ENCODED_LEN: usize = 8usize;
14808 fn deser(
14809 _version: MavlinkVersion,
14810 __input: &[u8],
14811 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14812 let avail_len = __input.len();
14813 let mut payload_buf = [0; Self::ENCODED_LEN];
14814 let mut buf = if avail_len < Self::ENCODED_LEN {
14815 payload_buf[0..avail_len].copy_from_slice(__input);
14816 Bytes::new(&payload_buf)
14817 } else {
14818 Bytes::new(__input)
14819 };
14820 let mut __struct = Self::default();
14821 __struct.target_system = buf.get_u8();
14822 __struct.target_component = buf.get_u8();
14823 let tmp = buf.get_u8();
14824 __struct.mavtype =
14825 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14826 enum_type: "MavMissionResult",
14827 value: tmp as u32,
14828 })?;
14829 let tmp = buf.get_u8();
14830 __struct.mission_type =
14831 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14832 enum_type: "MavMissionType",
14833 value: tmp as u32,
14834 })?;
14835 __struct.opaque_id = buf.get_u32_le();
14836 Ok(__struct)
14837 }
14838 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14839 let mut __tmp = BytesMut::new(bytes);
14840 #[allow(clippy::absurd_extreme_comparisons)]
14841 #[allow(unused_comparisons)]
14842 if __tmp.remaining() < Self::ENCODED_LEN {
14843 panic!(
14844 "buffer is too small (need {} bytes, but got {})",
14845 Self::ENCODED_LEN,
14846 __tmp.remaining(),
14847 )
14848 }
14849 __tmp.put_u8(self.target_system);
14850 __tmp.put_u8(self.target_component);
14851 __tmp.put_u8(self.mavtype as u8);
14852 __tmp.put_u8(self.mission_type as u8);
14853 __tmp.put_u32_le(self.opaque_id);
14854 if matches!(version, MavlinkVersion::V2) {
14855 let len = __tmp.len();
14856 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14857 } else {
14858 __tmp.len()
14859 }
14860 }
14861}
14862#[doc = "id: 233"]
14863#[doc = "RTCM message for injecting into the onboard GPS (used for DGPS)."]
14864#[derive(Debug, Clone, PartialEq)]
14865#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14866#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14867pub struct GPS_RTCM_DATA_DATA {
14868 #[doc = "LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order."]
14869 pub flags: u8,
14870 #[doc = "data length"]
14871 pub len: u8,
14872 #[doc = "RTCM message (may be fragmented)"]
14873 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14874 pub data: [u8; 180],
14875}
14876impl GPS_RTCM_DATA_DATA {
14877 pub const ENCODED_LEN: usize = 182usize;
14878 pub const DEFAULT: Self = Self {
14879 flags: 0_u8,
14880 len: 0_u8,
14881 data: [0_u8; 180usize],
14882 };
14883 #[cfg(feature = "arbitrary")]
14884 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14885 use arbitrary::{Arbitrary, Unstructured};
14886 let mut buf = [0u8; 1024];
14887 rng.fill_bytes(&mut buf);
14888 let mut unstructured = Unstructured::new(&buf);
14889 Self::arbitrary(&mut unstructured).unwrap_or_default()
14890 }
14891}
14892impl Default for GPS_RTCM_DATA_DATA {
14893 fn default() -> Self {
14894 Self::DEFAULT.clone()
14895 }
14896}
14897impl MessageData for GPS_RTCM_DATA_DATA {
14898 type Message = MavMessage;
14899 const ID: u32 = 233u32;
14900 const NAME: &'static str = "GPS_RTCM_DATA";
14901 const EXTRA_CRC: u8 = 35u8;
14902 const ENCODED_LEN: usize = 182usize;
14903 fn deser(
14904 _version: MavlinkVersion,
14905 __input: &[u8],
14906 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14907 let avail_len = __input.len();
14908 let mut payload_buf = [0; Self::ENCODED_LEN];
14909 let mut buf = if avail_len < Self::ENCODED_LEN {
14910 payload_buf[0..avail_len].copy_from_slice(__input);
14911 Bytes::new(&payload_buf)
14912 } else {
14913 Bytes::new(__input)
14914 };
14915 let mut __struct = Self::default();
14916 __struct.flags = buf.get_u8();
14917 __struct.len = buf.get_u8();
14918 for v in &mut __struct.data {
14919 let val = buf.get_u8();
14920 *v = val;
14921 }
14922 Ok(__struct)
14923 }
14924 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14925 let mut __tmp = BytesMut::new(bytes);
14926 #[allow(clippy::absurd_extreme_comparisons)]
14927 #[allow(unused_comparisons)]
14928 if __tmp.remaining() < Self::ENCODED_LEN {
14929 panic!(
14930 "buffer is too small (need {} bytes, but got {})",
14931 Self::ENCODED_LEN,
14932 __tmp.remaining(),
14933 )
14934 }
14935 __tmp.put_u8(self.flags);
14936 __tmp.put_u8(self.len);
14937 for val in &self.data {
14938 __tmp.put_u8(*val);
14939 }
14940 if matches!(version, MavlinkVersion::V2) {
14941 let len = __tmp.len();
14942 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14943 } else {
14944 __tmp.len()
14945 }
14946 }
14947}
14948#[doc = "id: 109"]
14949#[doc = "Status generated by radio and injected into MAVLink stream."]
14950#[derive(Debug, Clone, PartialEq)]
14951#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14952#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14953pub struct RADIO_STATUS_DATA {
14954 #[doc = "Count of radio packet receive errors (since boot)."]
14955 pub rxerrors: u16,
14956 #[doc = "Count of error corrected radio packets (since boot)."]
14957 pub fixed: u16,
14958 #[doc = "Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
14959 pub rssi: u8,
14960 #[doc = "Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
14961 pub remrssi: u8,
14962 #[doc = "Remaining free transmitter buffer space."]
14963 pub txbuf: u8,
14964 #[doc = "Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
14965 pub noise: u8,
14966 #[doc = "Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
14967 pub remnoise: u8,
14968}
14969impl RADIO_STATUS_DATA {
14970 pub const ENCODED_LEN: usize = 9usize;
14971 pub const DEFAULT: Self = Self {
14972 rxerrors: 0_u16,
14973 fixed: 0_u16,
14974 rssi: 0_u8,
14975 remrssi: 0_u8,
14976 txbuf: 0_u8,
14977 noise: 0_u8,
14978 remnoise: 0_u8,
14979 };
14980 #[cfg(feature = "arbitrary")]
14981 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14982 use arbitrary::{Arbitrary, Unstructured};
14983 let mut buf = [0u8; 1024];
14984 rng.fill_bytes(&mut buf);
14985 let mut unstructured = Unstructured::new(&buf);
14986 Self::arbitrary(&mut unstructured).unwrap_or_default()
14987 }
14988}
14989impl Default for RADIO_STATUS_DATA {
14990 fn default() -> Self {
14991 Self::DEFAULT.clone()
14992 }
14993}
14994impl MessageData for RADIO_STATUS_DATA {
14995 type Message = MavMessage;
14996 const ID: u32 = 109u32;
14997 const NAME: &'static str = "RADIO_STATUS";
14998 const EXTRA_CRC: u8 = 185u8;
14999 const ENCODED_LEN: usize = 9usize;
15000 fn deser(
15001 _version: MavlinkVersion,
15002 __input: &[u8],
15003 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15004 let avail_len = __input.len();
15005 let mut payload_buf = [0; Self::ENCODED_LEN];
15006 let mut buf = if avail_len < Self::ENCODED_LEN {
15007 payload_buf[0..avail_len].copy_from_slice(__input);
15008 Bytes::new(&payload_buf)
15009 } else {
15010 Bytes::new(__input)
15011 };
15012 let mut __struct = Self::default();
15013 __struct.rxerrors = buf.get_u16_le();
15014 __struct.fixed = buf.get_u16_le();
15015 __struct.rssi = buf.get_u8();
15016 __struct.remrssi = buf.get_u8();
15017 __struct.txbuf = buf.get_u8();
15018 __struct.noise = buf.get_u8();
15019 __struct.remnoise = buf.get_u8();
15020 Ok(__struct)
15021 }
15022 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15023 let mut __tmp = BytesMut::new(bytes);
15024 #[allow(clippy::absurd_extreme_comparisons)]
15025 #[allow(unused_comparisons)]
15026 if __tmp.remaining() < Self::ENCODED_LEN {
15027 panic!(
15028 "buffer is too small (need {} bytes, but got {})",
15029 Self::ENCODED_LEN,
15030 __tmp.remaining(),
15031 )
15032 }
15033 __tmp.put_u16_le(self.rxerrors);
15034 __tmp.put_u16_le(self.fixed);
15035 __tmp.put_u8(self.rssi);
15036 __tmp.put_u8(self.remrssi);
15037 __tmp.put_u8(self.txbuf);
15038 __tmp.put_u8(self.noise);
15039 __tmp.put_u8(self.remnoise);
15040 if matches!(version, MavlinkVersion::V2) {
15041 let len = __tmp.len();
15042 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15043 } else {
15044 __tmp.len()
15045 }
15046 }
15047}
15048#[doc = "id: 7"]
15049#[doc = "Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety."]
15050#[derive(Debug, Clone, PartialEq)]
15051#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15052#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15053pub struct AUTH_KEY_DATA {
15054 #[doc = "key"]
15055 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15056 pub key: [u8; 32],
15057}
15058impl AUTH_KEY_DATA {
15059 pub const ENCODED_LEN: usize = 32usize;
15060 pub const DEFAULT: Self = Self {
15061 key: [0_u8; 32usize],
15062 };
15063 #[cfg(feature = "arbitrary")]
15064 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15065 use arbitrary::{Arbitrary, Unstructured};
15066 let mut buf = [0u8; 1024];
15067 rng.fill_bytes(&mut buf);
15068 let mut unstructured = Unstructured::new(&buf);
15069 Self::arbitrary(&mut unstructured).unwrap_or_default()
15070 }
15071}
15072impl Default for AUTH_KEY_DATA {
15073 fn default() -> Self {
15074 Self::DEFAULT.clone()
15075 }
15076}
15077impl MessageData for AUTH_KEY_DATA {
15078 type Message = MavMessage;
15079 const ID: u32 = 7u32;
15080 const NAME: &'static str = "AUTH_KEY";
15081 const EXTRA_CRC: u8 = 119u8;
15082 const ENCODED_LEN: usize = 32usize;
15083 fn deser(
15084 _version: MavlinkVersion,
15085 __input: &[u8],
15086 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15087 let avail_len = __input.len();
15088 let mut payload_buf = [0; Self::ENCODED_LEN];
15089 let mut buf = if avail_len < Self::ENCODED_LEN {
15090 payload_buf[0..avail_len].copy_from_slice(__input);
15091 Bytes::new(&payload_buf)
15092 } else {
15093 Bytes::new(__input)
15094 };
15095 let mut __struct = Self::default();
15096 for v in &mut __struct.key {
15097 let val = buf.get_u8();
15098 *v = val;
15099 }
15100 Ok(__struct)
15101 }
15102 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15103 let mut __tmp = BytesMut::new(bytes);
15104 #[allow(clippy::absurd_extreme_comparisons)]
15105 #[allow(unused_comparisons)]
15106 if __tmp.remaining() < Self::ENCODED_LEN {
15107 panic!(
15108 "buffer is too small (need {} bytes, but got {})",
15109 Self::ENCODED_LEN,
15110 __tmp.remaining(),
15111 )
15112 }
15113 for val in &self.key {
15114 __tmp.put_u8(*val);
15115 }
15116 if matches!(version, MavlinkVersion::V2) {
15117 let len = __tmp.len();
15118 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15119 } else {
15120 __tmp.len()
15121 }
15122 }
15123}
15124#[doc = "id: 35"]
15125#[doc = "The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
15126#[derive(Debug, Clone, PartialEq)]
15127#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15128#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15129pub struct RC_CHANNELS_RAW_DATA {
15130 #[doc = "Timestamp (time since system boot)."]
15131 pub time_boot_ms: u32,
15132 #[doc = "RC channel 1 value."]
15133 pub chan1_raw: u16,
15134 #[doc = "RC channel 2 value."]
15135 pub chan2_raw: u16,
15136 #[doc = "RC channel 3 value."]
15137 pub chan3_raw: u16,
15138 #[doc = "RC channel 4 value."]
15139 pub chan4_raw: u16,
15140 #[doc = "RC channel 5 value."]
15141 pub chan5_raw: u16,
15142 #[doc = "RC channel 6 value."]
15143 pub chan6_raw: u16,
15144 #[doc = "RC channel 7 value."]
15145 pub chan7_raw: u16,
15146 #[doc = "RC channel 8 value."]
15147 pub chan8_raw: u16,
15148 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
15149 pub port: u8,
15150 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
15151 pub rssi: u8,
15152}
15153impl RC_CHANNELS_RAW_DATA {
15154 pub const ENCODED_LEN: usize = 22usize;
15155 pub const DEFAULT: Self = Self {
15156 time_boot_ms: 0_u32,
15157 chan1_raw: 0_u16,
15158 chan2_raw: 0_u16,
15159 chan3_raw: 0_u16,
15160 chan4_raw: 0_u16,
15161 chan5_raw: 0_u16,
15162 chan6_raw: 0_u16,
15163 chan7_raw: 0_u16,
15164 chan8_raw: 0_u16,
15165 port: 0_u8,
15166 rssi: 0_u8,
15167 };
15168 #[cfg(feature = "arbitrary")]
15169 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15170 use arbitrary::{Arbitrary, Unstructured};
15171 let mut buf = [0u8; 1024];
15172 rng.fill_bytes(&mut buf);
15173 let mut unstructured = Unstructured::new(&buf);
15174 Self::arbitrary(&mut unstructured).unwrap_or_default()
15175 }
15176}
15177impl Default for RC_CHANNELS_RAW_DATA {
15178 fn default() -> Self {
15179 Self::DEFAULT.clone()
15180 }
15181}
15182impl MessageData for RC_CHANNELS_RAW_DATA {
15183 type Message = MavMessage;
15184 const ID: u32 = 35u32;
15185 const NAME: &'static str = "RC_CHANNELS_RAW";
15186 const EXTRA_CRC: u8 = 244u8;
15187 const ENCODED_LEN: usize = 22usize;
15188 fn deser(
15189 _version: MavlinkVersion,
15190 __input: &[u8],
15191 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15192 let avail_len = __input.len();
15193 let mut payload_buf = [0; Self::ENCODED_LEN];
15194 let mut buf = if avail_len < Self::ENCODED_LEN {
15195 payload_buf[0..avail_len].copy_from_slice(__input);
15196 Bytes::new(&payload_buf)
15197 } else {
15198 Bytes::new(__input)
15199 };
15200 let mut __struct = Self::default();
15201 __struct.time_boot_ms = buf.get_u32_le();
15202 __struct.chan1_raw = buf.get_u16_le();
15203 __struct.chan2_raw = buf.get_u16_le();
15204 __struct.chan3_raw = buf.get_u16_le();
15205 __struct.chan4_raw = buf.get_u16_le();
15206 __struct.chan5_raw = buf.get_u16_le();
15207 __struct.chan6_raw = buf.get_u16_le();
15208 __struct.chan7_raw = buf.get_u16_le();
15209 __struct.chan8_raw = buf.get_u16_le();
15210 __struct.port = buf.get_u8();
15211 __struct.rssi = buf.get_u8();
15212 Ok(__struct)
15213 }
15214 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15215 let mut __tmp = BytesMut::new(bytes);
15216 #[allow(clippy::absurd_extreme_comparisons)]
15217 #[allow(unused_comparisons)]
15218 if __tmp.remaining() < Self::ENCODED_LEN {
15219 panic!(
15220 "buffer is too small (need {} bytes, but got {})",
15221 Self::ENCODED_LEN,
15222 __tmp.remaining(),
15223 )
15224 }
15225 __tmp.put_u32_le(self.time_boot_ms);
15226 __tmp.put_u16_le(self.chan1_raw);
15227 __tmp.put_u16_le(self.chan2_raw);
15228 __tmp.put_u16_le(self.chan3_raw);
15229 __tmp.put_u16_le(self.chan4_raw);
15230 __tmp.put_u16_le(self.chan5_raw);
15231 __tmp.put_u16_le(self.chan6_raw);
15232 __tmp.put_u16_le(self.chan7_raw);
15233 __tmp.put_u16_le(self.chan8_raw);
15234 __tmp.put_u8(self.port);
15235 __tmp.put_u8(self.rssi);
15236 if matches!(version, MavlinkVersion::V2) {
15237 let len = __tmp.len();
15238 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15239 } else {
15240 __tmp.len()
15241 }
15242 }
15243}
15244#[doc = "id: 120"]
15245#[doc = "Reply to LOG_REQUEST_DATA."]
15246#[derive(Debug, Clone, PartialEq)]
15247#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15248#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15249pub struct LOG_DATA_DATA {
15250 #[doc = "Offset into the log"]
15251 pub ofs: u32,
15252 #[doc = "Log id (from LOG_ENTRY reply)"]
15253 pub id: u16,
15254 #[doc = "Number of bytes (zero for end of log)"]
15255 pub count: u8,
15256 #[doc = "log data"]
15257 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15258 pub data: [u8; 90],
15259}
15260impl LOG_DATA_DATA {
15261 pub const ENCODED_LEN: usize = 97usize;
15262 pub const DEFAULT: Self = Self {
15263 ofs: 0_u32,
15264 id: 0_u16,
15265 count: 0_u8,
15266 data: [0_u8; 90usize],
15267 };
15268 #[cfg(feature = "arbitrary")]
15269 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15270 use arbitrary::{Arbitrary, Unstructured};
15271 let mut buf = [0u8; 1024];
15272 rng.fill_bytes(&mut buf);
15273 let mut unstructured = Unstructured::new(&buf);
15274 Self::arbitrary(&mut unstructured).unwrap_or_default()
15275 }
15276}
15277impl Default for LOG_DATA_DATA {
15278 fn default() -> Self {
15279 Self::DEFAULT.clone()
15280 }
15281}
15282impl MessageData for LOG_DATA_DATA {
15283 type Message = MavMessage;
15284 const ID: u32 = 120u32;
15285 const NAME: &'static str = "LOG_DATA";
15286 const EXTRA_CRC: u8 = 134u8;
15287 const ENCODED_LEN: usize = 97usize;
15288 fn deser(
15289 _version: MavlinkVersion,
15290 __input: &[u8],
15291 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15292 let avail_len = __input.len();
15293 let mut payload_buf = [0; Self::ENCODED_LEN];
15294 let mut buf = if avail_len < Self::ENCODED_LEN {
15295 payload_buf[0..avail_len].copy_from_slice(__input);
15296 Bytes::new(&payload_buf)
15297 } else {
15298 Bytes::new(__input)
15299 };
15300 let mut __struct = Self::default();
15301 __struct.ofs = buf.get_u32_le();
15302 __struct.id = buf.get_u16_le();
15303 __struct.count = buf.get_u8();
15304 for v in &mut __struct.data {
15305 let val = buf.get_u8();
15306 *v = val;
15307 }
15308 Ok(__struct)
15309 }
15310 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15311 let mut __tmp = BytesMut::new(bytes);
15312 #[allow(clippy::absurd_extreme_comparisons)]
15313 #[allow(unused_comparisons)]
15314 if __tmp.remaining() < Self::ENCODED_LEN {
15315 panic!(
15316 "buffer is too small (need {} bytes, but got {})",
15317 Self::ENCODED_LEN,
15318 __tmp.remaining(),
15319 )
15320 }
15321 __tmp.put_u32_le(self.ofs);
15322 __tmp.put_u16_le(self.id);
15323 __tmp.put_u8(self.count);
15324 for val in &self.data {
15325 __tmp.put_u8(*val);
15326 }
15327 if matches!(version, MavlinkVersion::V2) {
15328 let len = __tmp.len();
15329 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15330 } else {
15331 __tmp.len()
15332 }
15333 }
15334}
15335#[doc = "id: 22"]
15336#[doc = "Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
15337#[derive(Debug, Clone, PartialEq)]
15338#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15339#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15340pub struct PARAM_VALUE_DATA {
15341 #[doc = "Onboard parameter value"]
15342 pub param_value: f32,
15343 #[doc = "Total number of onboard parameters"]
15344 pub param_count: u16,
15345 #[doc = "Index of this onboard parameter"]
15346 pub param_index: u16,
15347 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
15348 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15349 pub param_id: [u8; 16],
15350 #[doc = "Onboard parameter type."]
15351 pub param_type: MavParamType,
15352}
15353impl PARAM_VALUE_DATA {
15354 pub const ENCODED_LEN: usize = 25usize;
15355 pub const DEFAULT: Self = Self {
15356 param_value: 0.0_f32,
15357 param_count: 0_u16,
15358 param_index: 0_u16,
15359 param_id: [0_u8; 16usize],
15360 param_type: MavParamType::DEFAULT,
15361 };
15362 #[cfg(feature = "arbitrary")]
15363 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15364 use arbitrary::{Arbitrary, Unstructured};
15365 let mut buf = [0u8; 1024];
15366 rng.fill_bytes(&mut buf);
15367 let mut unstructured = Unstructured::new(&buf);
15368 Self::arbitrary(&mut unstructured).unwrap_or_default()
15369 }
15370}
15371impl Default for PARAM_VALUE_DATA {
15372 fn default() -> Self {
15373 Self::DEFAULT.clone()
15374 }
15375}
15376impl MessageData for PARAM_VALUE_DATA {
15377 type Message = MavMessage;
15378 const ID: u32 = 22u32;
15379 const NAME: &'static str = "PARAM_VALUE";
15380 const EXTRA_CRC: u8 = 220u8;
15381 const ENCODED_LEN: usize = 25usize;
15382 fn deser(
15383 _version: MavlinkVersion,
15384 __input: &[u8],
15385 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15386 let avail_len = __input.len();
15387 let mut payload_buf = [0; Self::ENCODED_LEN];
15388 let mut buf = if avail_len < Self::ENCODED_LEN {
15389 payload_buf[0..avail_len].copy_from_slice(__input);
15390 Bytes::new(&payload_buf)
15391 } else {
15392 Bytes::new(__input)
15393 };
15394 let mut __struct = Self::default();
15395 __struct.param_value = buf.get_f32_le();
15396 __struct.param_count = buf.get_u16_le();
15397 __struct.param_index = buf.get_u16_le();
15398 for v in &mut __struct.param_id {
15399 let val = buf.get_u8();
15400 *v = val;
15401 }
15402 let tmp = buf.get_u8();
15403 __struct.param_type =
15404 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15405 enum_type: "MavParamType",
15406 value: tmp as u32,
15407 })?;
15408 Ok(__struct)
15409 }
15410 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15411 let mut __tmp = BytesMut::new(bytes);
15412 #[allow(clippy::absurd_extreme_comparisons)]
15413 #[allow(unused_comparisons)]
15414 if __tmp.remaining() < Self::ENCODED_LEN {
15415 panic!(
15416 "buffer is too small (need {} bytes, but got {})",
15417 Self::ENCODED_LEN,
15418 __tmp.remaining(),
15419 )
15420 }
15421 __tmp.put_f32_le(self.param_value);
15422 __tmp.put_u16_le(self.param_count);
15423 __tmp.put_u16_le(self.param_index);
15424 for val in &self.param_id {
15425 __tmp.put_u8(*val);
15426 }
15427 __tmp.put_u8(self.param_type as u8);
15428 if matches!(version, MavlinkVersion::V2) {
15429 let len = __tmp.len();
15430 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15431 } else {
15432 __tmp.len()
15433 }
15434 }
15435}
15436#[doc = "id: 138"]
15437#[doc = "Motion capture attitude and position."]
15438#[derive(Debug, Clone, PartialEq)]
15439#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15440#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15441pub struct ATT_POS_MOCAP_DATA {
15442 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15443 pub time_usec: u64,
15444 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
15445 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15446 pub q: [f32; 4],
15447 #[doc = "X position (NED)"]
15448 pub x: f32,
15449 #[doc = "Y position (NED)"]
15450 pub y: f32,
15451 #[doc = "Z position (NED)"]
15452 pub z: f32,
15453 #[doc = "Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
15454 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15455 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15456 pub covariance: [f32; 21],
15457}
15458impl ATT_POS_MOCAP_DATA {
15459 pub const ENCODED_LEN: usize = 120usize;
15460 pub const DEFAULT: Self = Self {
15461 time_usec: 0_u64,
15462 q: [0.0_f32; 4usize],
15463 x: 0.0_f32,
15464 y: 0.0_f32,
15465 z: 0.0_f32,
15466 covariance: [0.0_f32; 21usize],
15467 };
15468 #[cfg(feature = "arbitrary")]
15469 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15470 use arbitrary::{Arbitrary, Unstructured};
15471 let mut buf = [0u8; 1024];
15472 rng.fill_bytes(&mut buf);
15473 let mut unstructured = Unstructured::new(&buf);
15474 Self::arbitrary(&mut unstructured).unwrap_or_default()
15475 }
15476}
15477impl Default for ATT_POS_MOCAP_DATA {
15478 fn default() -> Self {
15479 Self::DEFAULT.clone()
15480 }
15481}
15482impl MessageData for ATT_POS_MOCAP_DATA {
15483 type Message = MavMessage;
15484 const ID: u32 = 138u32;
15485 const NAME: &'static str = "ATT_POS_MOCAP";
15486 const EXTRA_CRC: u8 = 109u8;
15487 const ENCODED_LEN: usize = 120usize;
15488 fn deser(
15489 _version: MavlinkVersion,
15490 __input: &[u8],
15491 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15492 let avail_len = __input.len();
15493 let mut payload_buf = [0; Self::ENCODED_LEN];
15494 let mut buf = if avail_len < Self::ENCODED_LEN {
15495 payload_buf[0..avail_len].copy_from_slice(__input);
15496 Bytes::new(&payload_buf)
15497 } else {
15498 Bytes::new(__input)
15499 };
15500 let mut __struct = Self::default();
15501 __struct.time_usec = buf.get_u64_le();
15502 for v in &mut __struct.q {
15503 let val = buf.get_f32_le();
15504 *v = val;
15505 }
15506 __struct.x = buf.get_f32_le();
15507 __struct.y = buf.get_f32_le();
15508 __struct.z = buf.get_f32_le();
15509 for v in &mut __struct.covariance {
15510 let val = buf.get_f32_le();
15511 *v = val;
15512 }
15513 Ok(__struct)
15514 }
15515 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15516 let mut __tmp = BytesMut::new(bytes);
15517 #[allow(clippy::absurd_extreme_comparisons)]
15518 #[allow(unused_comparisons)]
15519 if __tmp.remaining() < Self::ENCODED_LEN {
15520 panic!(
15521 "buffer is too small (need {} bytes, but got {})",
15522 Self::ENCODED_LEN,
15523 __tmp.remaining(),
15524 )
15525 }
15526 __tmp.put_u64_le(self.time_usec);
15527 for val in &self.q {
15528 __tmp.put_f32_le(*val);
15529 }
15530 __tmp.put_f32_le(self.x);
15531 __tmp.put_f32_le(self.y);
15532 __tmp.put_f32_le(self.z);
15533 for val in &self.covariance {
15534 __tmp.put_f32_le(*val);
15535 }
15536 if matches!(version, MavlinkVersion::V2) {
15537 let len = __tmp.len();
15538 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15539 } else {
15540 __tmp.len()
15541 }
15542 }
15543}
15544#[doc = "id: 243"]
15545#[doc = "Sets the home position. \tThe home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
15546#[derive(Debug, Clone, PartialEq)]
15547#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15548#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15549pub struct SET_HOME_POSITION_DATA {
15550 #[doc = "Latitude (WGS84)"]
15551 pub latitude: i32,
15552 #[doc = "Longitude (WGS84)"]
15553 pub longitude: i32,
15554 #[doc = "Altitude (MSL). Positive for up."]
15555 pub altitude: i32,
15556 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
15557 pub x: f32,
15558 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
15559 pub y: f32,
15560 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
15561 pub z: f32,
15562 #[doc = "World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground"]
15563 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15564 pub q: [f32; 4],
15565 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
15566 pub approach_x: f32,
15567 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
15568 pub approach_y: f32,
15569 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
15570 pub approach_z: f32,
15571 #[doc = "System ID."]
15572 pub target_system: u8,
15573 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15574 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15575 pub time_usec: u64,
15576}
15577impl SET_HOME_POSITION_DATA {
15578 pub const ENCODED_LEN: usize = 61usize;
15579 pub const DEFAULT: Self = Self {
15580 latitude: 0_i32,
15581 longitude: 0_i32,
15582 altitude: 0_i32,
15583 x: 0.0_f32,
15584 y: 0.0_f32,
15585 z: 0.0_f32,
15586 q: [0.0_f32; 4usize],
15587 approach_x: 0.0_f32,
15588 approach_y: 0.0_f32,
15589 approach_z: 0.0_f32,
15590 target_system: 0_u8,
15591 time_usec: 0_u64,
15592 };
15593 #[cfg(feature = "arbitrary")]
15594 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15595 use arbitrary::{Arbitrary, Unstructured};
15596 let mut buf = [0u8; 1024];
15597 rng.fill_bytes(&mut buf);
15598 let mut unstructured = Unstructured::new(&buf);
15599 Self::arbitrary(&mut unstructured).unwrap_or_default()
15600 }
15601}
15602impl Default for SET_HOME_POSITION_DATA {
15603 fn default() -> Self {
15604 Self::DEFAULT.clone()
15605 }
15606}
15607impl MessageData for SET_HOME_POSITION_DATA {
15608 type Message = MavMessage;
15609 const ID: u32 = 243u32;
15610 const NAME: &'static str = "SET_HOME_POSITION";
15611 const EXTRA_CRC: u8 = 85u8;
15612 const ENCODED_LEN: usize = 61usize;
15613 fn deser(
15614 _version: MavlinkVersion,
15615 __input: &[u8],
15616 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15617 let avail_len = __input.len();
15618 let mut payload_buf = [0; Self::ENCODED_LEN];
15619 let mut buf = if avail_len < Self::ENCODED_LEN {
15620 payload_buf[0..avail_len].copy_from_slice(__input);
15621 Bytes::new(&payload_buf)
15622 } else {
15623 Bytes::new(__input)
15624 };
15625 let mut __struct = Self::default();
15626 __struct.latitude = buf.get_i32_le();
15627 __struct.longitude = buf.get_i32_le();
15628 __struct.altitude = buf.get_i32_le();
15629 __struct.x = buf.get_f32_le();
15630 __struct.y = buf.get_f32_le();
15631 __struct.z = buf.get_f32_le();
15632 for v in &mut __struct.q {
15633 let val = buf.get_f32_le();
15634 *v = val;
15635 }
15636 __struct.approach_x = buf.get_f32_le();
15637 __struct.approach_y = buf.get_f32_le();
15638 __struct.approach_z = buf.get_f32_le();
15639 __struct.target_system = buf.get_u8();
15640 __struct.time_usec = buf.get_u64_le();
15641 Ok(__struct)
15642 }
15643 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15644 let mut __tmp = BytesMut::new(bytes);
15645 #[allow(clippy::absurd_extreme_comparisons)]
15646 #[allow(unused_comparisons)]
15647 if __tmp.remaining() < Self::ENCODED_LEN {
15648 panic!(
15649 "buffer is too small (need {} bytes, but got {})",
15650 Self::ENCODED_LEN,
15651 __tmp.remaining(),
15652 )
15653 }
15654 __tmp.put_i32_le(self.latitude);
15655 __tmp.put_i32_le(self.longitude);
15656 __tmp.put_i32_le(self.altitude);
15657 __tmp.put_f32_le(self.x);
15658 __tmp.put_f32_le(self.y);
15659 __tmp.put_f32_le(self.z);
15660 for val in &self.q {
15661 __tmp.put_f32_le(*val);
15662 }
15663 __tmp.put_f32_le(self.approach_x);
15664 __tmp.put_f32_le(self.approach_y);
15665 __tmp.put_f32_le(self.approach_z);
15666 __tmp.put_u8(self.target_system);
15667 __tmp.put_u64_le(self.time_usec);
15668 if matches!(version, MavlinkVersion::V2) {
15669 let len = __tmp.len();
15670 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15671 } else {
15672 __tmp.len()
15673 }
15674 }
15675}
15676#[doc = "id: 397"]
15677#[doc = "Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. This contains the MAVLink FTP URI and CRC for the component's general metadata file. The file must be hosted on the component, and may be xz compressed. The file CRC can be used for file caching. The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. For more information see: <https://mavlink.io/en/services/component_information.html>. Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION."]
15678#[derive(Debug, Clone, PartialEq)]
15679#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15680#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15681pub struct COMPONENT_METADATA_DATA {
15682 #[doc = "Timestamp (time since system boot)."]
15683 pub time_boot_ms: u32,
15684 #[doc = "CRC32 of the general metadata file."]
15685 pub file_crc: u32,
15686 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
15687 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15688 pub uri: [u8; 100],
15689}
15690impl COMPONENT_METADATA_DATA {
15691 pub const ENCODED_LEN: usize = 108usize;
15692 pub const DEFAULT: Self = Self {
15693 time_boot_ms: 0_u32,
15694 file_crc: 0_u32,
15695 uri: [0_u8; 100usize],
15696 };
15697 #[cfg(feature = "arbitrary")]
15698 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15699 use arbitrary::{Arbitrary, Unstructured};
15700 let mut buf = [0u8; 1024];
15701 rng.fill_bytes(&mut buf);
15702 let mut unstructured = Unstructured::new(&buf);
15703 Self::arbitrary(&mut unstructured).unwrap_or_default()
15704 }
15705}
15706impl Default for COMPONENT_METADATA_DATA {
15707 fn default() -> Self {
15708 Self::DEFAULT.clone()
15709 }
15710}
15711impl MessageData for COMPONENT_METADATA_DATA {
15712 type Message = MavMessage;
15713 const ID: u32 = 397u32;
15714 const NAME: &'static str = "COMPONENT_METADATA";
15715 const EXTRA_CRC: u8 = 182u8;
15716 const ENCODED_LEN: usize = 108usize;
15717 fn deser(
15718 _version: MavlinkVersion,
15719 __input: &[u8],
15720 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15721 let avail_len = __input.len();
15722 let mut payload_buf = [0; Self::ENCODED_LEN];
15723 let mut buf = if avail_len < Self::ENCODED_LEN {
15724 payload_buf[0..avail_len].copy_from_slice(__input);
15725 Bytes::new(&payload_buf)
15726 } else {
15727 Bytes::new(__input)
15728 };
15729 let mut __struct = Self::default();
15730 __struct.time_boot_ms = buf.get_u32_le();
15731 __struct.file_crc = buf.get_u32_le();
15732 for v in &mut __struct.uri {
15733 let val = buf.get_u8();
15734 *v = val;
15735 }
15736 Ok(__struct)
15737 }
15738 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15739 let mut __tmp = BytesMut::new(bytes);
15740 #[allow(clippy::absurd_extreme_comparisons)]
15741 #[allow(unused_comparisons)]
15742 if __tmp.remaining() < Self::ENCODED_LEN {
15743 panic!(
15744 "buffer is too small (need {} bytes, but got {})",
15745 Self::ENCODED_LEN,
15746 __tmp.remaining(),
15747 )
15748 }
15749 __tmp.put_u32_le(self.time_boot_ms);
15750 __tmp.put_u32_le(self.file_crc);
15751 for val in &self.uri {
15752 __tmp.put_u8(*val);
15753 }
15754 if matches!(version, MavlinkVersion::V2) {
15755 let len = __tmp.len();
15756 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15757 } else {
15758 __tmp.len()
15759 }
15760 }
15761}
15762#[doc = "id: 9005"]
15763#[doc = "Winch status."]
15764#[derive(Debug, Clone, PartialEq)]
15765#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15766#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15767pub struct WINCH_STATUS_DATA {
15768 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
15769 pub time_usec: u64,
15770 #[doc = "Length of line released. NaN if unknown"]
15771 pub line_length: f32,
15772 #[doc = "Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown"]
15773 pub speed: f32,
15774 #[doc = "Tension on the line. NaN if unknown"]
15775 pub tension: f32,
15776 #[doc = "Voltage of the battery supplying the winch. NaN if unknown"]
15777 pub voltage: f32,
15778 #[doc = "Current draw from the winch. NaN if unknown"]
15779 pub current: f32,
15780 #[doc = "Status flags"]
15781 pub status: MavWinchStatusFlag,
15782 #[doc = "Temperature of the motor. INT16_MAX if unknown"]
15783 pub temperature: i16,
15784}
15785impl WINCH_STATUS_DATA {
15786 pub const ENCODED_LEN: usize = 34usize;
15787 pub const DEFAULT: Self = Self {
15788 time_usec: 0_u64,
15789 line_length: 0.0_f32,
15790 speed: 0.0_f32,
15791 tension: 0.0_f32,
15792 voltage: 0.0_f32,
15793 current: 0.0_f32,
15794 status: MavWinchStatusFlag::DEFAULT,
15795 temperature: 0_i16,
15796 };
15797 #[cfg(feature = "arbitrary")]
15798 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15799 use arbitrary::{Arbitrary, Unstructured};
15800 let mut buf = [0u8; 1024];
15801 rng.fill_bytes(&mut buf);
15802 let mut unstructured = Unstructured::new(&buf);
15803 Self::arbitrary(&mut unstructured).unwrap_or_default()
15804 }
15805}
15806impl Default for WINCH_STATUS_DATA {
15807 fn default() -> Self {
15808 Self::DEFAULT.clone()
15809 }
15810}
15811impl MessageData for WINCH_STATUS_DATA {
15812 type Message = MavMessage;
15813 const ID: u32 = 9005u32;
15814 const NAME: &'static str = "WINCH_STATUS";
15815 const EXTRA_CRC: u8 = 117u8;
15816 const ENCODED_LEN: usize = 34usize;
15817 fn deser(
15818 _version: MavlinkVersion,
15819 __input: &[u8],
15820 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15821 let avail_len = __input.len();
15822 let mut payload_buf = [0; Self::ENCODED_LEN];
15823 let mut buf = if avail_len < Self::ENCODED_LEN {
15824 payload_buf[0..avail_len].copy_from_slice(__input);
15825 Bytes::new(&payload_buf)
15826 } else {
15827 Bytes::new(__input)
15828 };
15829 let mut __struct = Self::default();
15830 __struct.time_usec = buf.get_u64_le();
15831 __struct.line_length = buf.get_f32_le();
15832 __struct.speed = buf.get_f32_le();
15833 __struct.tension = buf.get_f32_le();
15834 __struct.voltage = buf.get_f32_le();
15835 __struct.current = buf.get_f32_le();
15836 let tmp = buf.get_u32_le();
15837 __struct.status = MavWinchStatusFlag::from_bits(tmp & MavWinchStatusFlag::all().bits())
15838 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
15839 flag_type: "MavWinchStatusFlag",
15840 value: tmp as u32,
15841 })?;
15842 __struct.temperature = buf.get_i16_le();
15843 Ok(__struct)
15844 }
15845 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15846 let mut __tmp = BytesMut::new(bytes);
15847 #[allow(clippy::absurd_extreme_comparisons)]
15848 #[allow(unused_comparisons)]
15849 if __tmp.remaining() < Self::ENCODED_LEN {
15850 panic!(
15851 "buffer is too small (need {} bytes, but got {})",
15852 Self::ENCODED_LEN,
15853 __tmp.remaining(),
15854 )
15855 }
15856 __tmp.put_u64_le(self.time_usec);
15857 __tmp.put_f32_le(self.line_length);
15858 __tmp.put_f32_le(self.speed);
15859 __tmp.put_f32_le(self.tension);
15860 __tmp.put_f32_le(self.voltage);
15861 __tmp.put_f32_le(self.current);
15862 __tmp.put_u32_le(self.status.bits());
15863 __tmp.put_i16_le(self.temperature);
15864 if matches!(version, MavlinkVersion::V2) {
15865 let len = __tmp.len();
15866 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15867 } else {
15868 __tmp.len()
15869 }
15870 }
15871}
15872#[doc = "id: 134"]
15873#[doc = "Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
15874#[derive(Debug, Clone, PartialEq)]
15875#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15876#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15877pub struct TERRAIN_DATA_DATA {
15878 #[doc = "Latitude of SW corner of first grid"]
15879 pub lat: i32,
15880 #[doc = "Longitude of SW corner of first grid"]
15881 pub lon: i32,
15882 #[doc = "Grid spacing"]
15883 pub grid_spacing: u16,
15884 #[doc = "Terrain data MSL"]
15885 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15886 pub data: [i16; 16],
15887 #[doc = "bit within the terrain request mask"]
15888 pub gridbit: u8,
15889}
15890impl TERRAIN_DATA_DATA {
15891 pub const ENCODED_LEN: usize = 43usize;
15892 pub const DEFAULT: Self = Self {
15893 lat: 0_i32,
15894 lon: 0_i32,
15895 grid_spacing: 0_u16,
15896 data: [0_i16; 16usize],
15897 gridbit: 0_u8,
15898 };
15899 #[cfg(feature = "arbitrary")]
15900 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15901 use arbitrary::{Arbitrary, Unstructured};
15902 let mut buf = [0u8; 1024];
15903 rng.fill_bytes(&mut buf);
15904 let mut unstructured = Unstructured::new(&buf);
15905 Self::arbitrary(&mut unstructured).unwrap_or_default()
15906 }
15907}
15908impl Default for TERRAIN_DATA_DATA {
15909 fn default() -> Self {
15910 Self::DEFAULT.clone()
15911 }
15912}
15913impl MessageData for TERRAIN_DATA_DATA {
15914 type Message = MavMessage;
15915 const ID: u32 = 134u32;
15916 const NAME: &'static str = "TERRAIN_DATA";
15917 const EXTRA_CRC: u8 = 229u8;
15918 const ENCODED_LEN: usize = 43usize;
15919 fn deser(
15920 _version: MavlinkVersion,
15921 __input: &[u8],
15922 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15923 let avail_len = __input.len();
15924 let mut payload_buf = [0; Self::ENCODED_LEN];
15925 let mut buf = if avail_len < Self::ENCODED_LEN {
15926 payload_buf[0..avail_len].copy_from_slice(__input);
15927 Bytes::new(&payload_buf)
15928 } else {
15929 Bytes::new(__input)
15930 };
15931 let mut __struct = Self::default();
15932 __struct.lat = buf.get_i32_le();
15933 __struct.lon = buf.get_i32_le();
15934 __struct.grid_spacing = buf.get_u16_le();
15935 for v in &mut __struct.data {
15936 let val = buf.get_i16_le();
15937 *v = val;
15938 }
15939 __struct.gridbit = buf.get_u8();
15940 Ok(__struct)
15941 }
15942 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15943 let mut __tmp = BytesMut::new(bytes);
15944 #[allow(clippy::absurd_extreme_comparisons)]
15945 #[allow(unused_comparisons)]
15946 if __tmp.remaining() < Self::ENCODED_LEN {
15947 panic!(
15948 "buffer is too small (need {} bytes, but got {})",
15949 Self::ENCODED_LEN,
15950 __tmp.remaining(),
15951 )
15952 }
15953 __tmp.put_i32_le(self.lat);
15954 __tmp.put_i32_le(self.lon);
15955 __tmp.put_u16_le(self.grid_spacing);
15956 for val in &self.data {
15957 __tmp.put_i16_le(*val);
15958 }
15959 __tmp.put_u8(self.gridbit);
15960 if matches!(version, MavlinkVersion::V2) {
15961 let len = __tmp.len();
15962 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15963 } else {
15964 __tmp.len()
15965 }
15966 }
15967}
15968#[doc = "id: 130"]
15969#[doc = "Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
15970#[derive(Debug, Clone, PartialEq)]
15971#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15972#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15973pub struct DATA_TRANSMISSION_HANDSHAKE_DATA {
15974 #[doc = "total data size (set on ACK only)."]
15975 pub size: u32,
15976 #[doc = "Width of a matrix or image."]
15977 pub width: u16,
15978 #[doc = "Height of a matrix or image."]
15979 pub height: u16,
15980 #[doc = "Number of packets being sent (set on ACK only)."]
15981 pub packets: u16,
15982 #[doc = "Type of requested/acknowledged data."]
15983 pub mavtype: MavlinkDataStreamType,
15984 #[doc = "Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)."]
15985 pub payload: u8,
15986 #[doc = "JPEG quality. Values: [1-100]."]
15987 pub jpg_quality: u8,
15988}
15989impl DATA_TRANSMISSION_HANDSHAKE_DATA {
15990 pub const ENCODED_LEN: usize = 13usize;
15991 pub const DEFAULT: Self = Self {
15992 size: 0_u32,
15993 width: 0_u16,
15994 height: 0_u16,
15995 packets: 0_u16,
15996 mavtype: MavlinkDataStreamType::DEFAULT,
15997 payload: 0_u8,
15998 jpg_quality: 0_u8,
15999 };
16000 #[cfg(feature = "arbitrary")]
16001 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16002 use arbitrary::{Arbitrary, Unstructured};
16003 let mut buf = [0u8; 1024];
16004 rng.fill_bytes(&mut buf);
16005 let mut unstructured = Unstructured::new(&buf);
16006 Self::arbitrary(&mut unstructured).unwrap_or_default()
16007 }
16008}
16009impl Default for DATA_TRANSMISSION_HANDSHAKE_DATA {
16010 fn default() -> Self {
16011 Self::DEFAULT.clone()
16012 }
16013}
16014impl MessageData for DATA_TRANSMISSION_HANDSHAKE_DATA {
16015 type Message = MavMessage;
16016 const ID: u32 = 130u32;
16017 const NAME: &'static str = "DATA_TRANSMISSION_HANDSHAKE";
16018 const EXTRA_CRC: u8 = 29u8;
16019 const ENCODED_LEN: usize = 13usize;
16020 fn deser(
16021 _version: MavlinkVersion,
16022 __input: &[u8],
16023 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16024 let avail_len = __input.len();
16025 let mut payload_buf = [0; Self::ENCODED_LEN];
16026 let mut buf = if avail_len < Self::ENCODED_LEN {
16027 payload_buf[0..avail_len].copy_from_slice(__input);
16028 Bytes::new(&payload_buf)
16029 } else {
16030 Bytes::new(__input)
16031 };
16032 let mut __struct = Self::default();
16033 __struct.size = buf.get_u32_le();
16034 __struct.width = buf.get_u16_le();
16035 __struct.height = buf.get_u16_le();
16036 __struct.packets = buf.get_u16_le();
16037 let tmp = buf.get_u8();
16038 __struct.mavtype =
16039 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16040 enum_type: "MavlinkDataStreamType",
16041 value: tmp as u32,
16042 })?;
16043 __struct.payload = buf.get_u8();
16044 __struct.jpg_quality = buf.get_u8();
16045 Ok(__struct)
16046 }
16047 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16048 let mut __tmp = BytesMut::new(bytes);
16049 #[allow(clippy::absurd_extreme_comparisons)]
16050 #[allow(unused_comparisons)]
16051 if __tmp.remaining() < Self::ENCODED_LEN {
16052 panic!(
16053 "buffer is too small (need {} bytes, but got {})",
16054 Self::ENCODED_LEN,
16055 __tmp.remaining(),
16056 )
16057 }
16058 __tmp.put_u32_le(self.size);
16059 __tmp.put_u16_le(self.width);
16060 __tmp.put_u16_le(self.height);
16061 __tmp.put_u16_le(self.packets);
16062 __tmp.put_u8(self.mavtype as u8);
16063 __tmp.put_u8(self.payload);
16064 __tmp.put_u8(self.jpg_quality);
16065 if matches!(version, MavlinkVersion::V2) {
16066 let len = __tmp.len();
16067 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16068 } else {
16069 __tmp.len()
16070 }
16071 }
16072}
16073#[doc = "id: 290"]
16074#[doc = "ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data."]
16075#[derive(Debug, Clone, PartialEq)]
16076#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16077#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16078pub struct ESC_INFO_DATA {
16079 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
16080 pub time_usec: u64,
16081 #[doc = "Number of reported errors by each ESC since boot."]
16082 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16083 pub error_count: [u32; 4],
16084 #[doc = "Counter of data packets received."]
16085 pub counter: u16,
16086 #[doc = "Bitmap of ESC failure flags."]
16087 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16088 pub failure_flags: [u16; 4],
16089 #[doc = "Temperature of each ESC. INT16_MAX: if data not supplied by ESC."]
16090 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16091 pub temperature: [i16; 4],
16092 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
16093 pub index: u8,
16094 #[doc = "Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data."]
16095 pub count: u8,
16096 #[doc = "Connection type protocol for all ESC."]
16097 pub connection_type: EscConnectionType,
16098 #[doc = "Information regarding online/offline status of each ESC."]
16099 pub info: u8,
16100}
16101impl ESC_INFO_DATA {
16102 pub const ENCODED_LEN: usize = 46usize;
16103 pub const DEFAULT: Self = Self {
16104 time_usec: 0_u64,
16105 error_count: [0_u32; 4usize],
16106 counter: 0_u16,
16107 failure_flags: [0_u16; 4usize],
16108 temperature: [0_i16; 4usize],
16109 index: 0_u8,
16110 count: 0_u8,
16111 connection_type: EscConnectionType::DEFAULT,
16112 info: 0_u8,
16113 };
16114 #[cfg(feature = "arbitrary")]
16115 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16116 use arbitrary::{Arbitrary, Unstructured};
16117 let mut buf = [0u8; 1024];
16118 rng.fill_bytes(&mut buf);
16119 let mut unstructured = Unstructured::new(&buf);
16120 Self::arbitrary(&mut unstructured).unwrap_or_default()
16121 }
16122}
16123impl Default for ESC_INFO_DATA {
16124 fn default() -> Self {
16125 Self::DEFAULT.clone()
16126 }
16127}
16128impl MessageData for ESC_INFO_DATA {
16129 type Message = MavMessage;
16130 const ID: u32 = 290u32;
16131 const NAME: &'static str = "ESC_INFO";
16132 const EXTRA_CRC: u8 = 251u8;
16133 const ENCODED_LEN: usize = 46usize;
16134 fn deser(
16135 _version: MavlinkVersion,
16136 __input: &[u8],
16137 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16138 let avail_len = __input.len();
16139 let mut payload_buf = [0; Self::ENCODED_LEN];
16140 let mut buf = if avail_len < Self::ENCODED_LEN {
16141 payload_buf[0..avail_len].copy_from_slice(__input);
16142 Bytes::new(&payload_buf)
16143 } else {
16144 Bytes::new(__input)
16145 };
16146 let mut __struct = Self::default();
16147 __struct.time_usec = buf.get_u64_le();
16148 for v in &mut __struct.error_count {
16149 let val = buf.get_u32_le();
16150 *v = val;
16151 }
16152 __struct.counter = buf.get_u16_le();
16153 for v in &mut __struct.failure_flags {
16154 let val = buf.get_u16_le();
16155 *v = val;
16156 }
16157 for v in &mut __struct.temperature {
16158 let val = buf.get_i16_le();
16159 *v = val;
16160 }
16161 __struct.index = buf.get_u8();
16162 __struct.count = buf.get_u8();
16163 let tmp = buf.get_u8();
16164 __struct.connection_type =
16165 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16166 enum_type: "EscConnectionType",
16167 value: tmp as u32,
16168 })?;
16169 __struct.info = buf.get_u8();
16170 Ok(__struct)
16171 }
16172 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16173 let mut __tmp = BytesMut::new(bytes);
16174 #[allow(clippy::absurd_extreme_comparisons)]
16175 #[allow(unused_comparisons)]
16176 if __tmp.remaining() < Self::ENCODED_LEN {
16177 panic!(
16178 "buffer is too small (need {} bytes, but got {})",
16179 Self::ENCODED_LEN,
16180 __tmp.remaining(),
16181 )
16182 }
16183 __tmp.put_u64_le(self.time_usec);
16184 for val in &self.error_count {
16185 __tmp.put_u32_le(*val);
16186 }
16187 __tmp.put_u16_le(self.counter);
16188 for val in &self.failure_flags {
16189 __tmp.put_u16_le(*val);
16190 }
16191 for val in &self.temperature {
16192 __tmp.put_i16_le(*val);
16193 }
16194 __tmp.put_u8(self.index);
16195 __tmp.put_u8(self.count);
16196 __tmp.put_u8(self.connection_type as u8);
16197 __tmp.put_u8(self.info);
16198 if matches!(version, MavlinkVersion::V2) {
16199 let len = __tmp.len();
16200 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16201 } else {
16202 __tmp.len()
16203 }
16204 }
16205}
16206#[doc = "id: 36"]
16207#[doc = "Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%."]
16208#[derive(Debug, Clone, PartialEq)]
16209#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16210#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16211pub struct SERVO_OUTPUT_RAW_DATA {
16212 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16213 pub time_usec: u32,
16214 #[doc = "Servo output 1 value"]
16215 pub servo1_raw: u16,
16216 #[doc = "Servo output 2 value"]
16217 pub servo2_raw: u16,
16218 #[doc = "Servo output 3 value"]
16219 pub servo3_raw: u16,
16220 #[doc = "Servo output 4 value"]
16221 pub servo4_raw: u16,
16222 #[doc = "Servo output 5 value"]
16223 pub servo5_raw: u16,
16224 #[doc = "Servo output 6 value"]
16225 pub servo6_raw: u16,
16226 #[doc = "Servo output 7 value"]
16227 pub servo7_raw: u16,
16228 #[doc = "Servo output 8 value"]
16229 pub servo8_raw: u16,
16230 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
16231 pub port: u8,
16232 #[doc = "Servo output 9 value"]
16233 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16234 pub servo9_raw: u16,
16235 #[doc = "Servo output 10 value"]
16236 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16237 pub servo10_raw: u16,
16238 #[doc = "Servo output 11 value"]
16239 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16240 pub servo11_raw: u16,
16241 #[doc = "Servo output 12 value"]
16242 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16243 pub servo12_raw: u16,
16244 #[doc = "Servo output 13 value"]
16245 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16246 pub servo13_raw: u16,
16247 #[doc = "Servo output 14 value"]
16248 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16249 pub servo14_raw: u16,
16250 #[doc = "Servo output 15 value"]
16251 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16252 pub servo15_raw: u16,
16253 #[doc = "Servo output 16 value"]
16254 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16255 pub servo16_raw: u16,
16256}
16257impl SERVO_OUTPUT_RAW_DATA {
16258 pub const ENCODED_LEN: usize = 37usize;
16259 pub const DEFAULT: Self = Self {
16260 time_usec: 0_u32,
16261 servo1_raw: 0_u16,
16262 servo2_raw: 0_u16,
16263 servo3_raw: 0_u16,
16264 servo4_raw: 0_u16,
16265 servo5_raw: 0_u16,
16266 servo6_raw: 0_u16,
16267 servo7_raw: 0_u16,
16268 servo8_raw: 0_u16,
16269 port: 0_u8,
16270 servo9_raw: 0_u16,
16271 servo10_raw: 0_u16,
16272 servo11_raw: 0_u16,
16273 servo12_raw: 0_u16,
16274 servo13_raw: 0_u16,
16275 servo14_raw: 0_u16,
16276 servo15_raw: 0_u16,
16277 servo16_raw: 0_u16,
16278 };
16279 #[cfg(feature = "arbitrary")]
16280 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16281 use arbitrary::{Arbitrary, Unstructured};
16282 let mut buf = [0u8; 1024];
16283 rng.fill_bytes(&mut buf);
16284 let mut unstructured = Unstructured::new(&buf);
16285 Self::arbitrary(&mut unstructured).unwrap_or_default()
16286 }
16287}
16288impl Default for SERVO_OUTPUT_RAW_DATA {
16289 fn default() -> Self {
16290 Self::DEFAULT.clone()
16291 }
16292}
16293impl MessageData for SERVO_OUTPUT_RAW_DATA {
16294 type Message = MavMessage;
16295 const ID: u32 = 36u32;
16296 const NAME: &'static str = "SERVO_OUTPUT_RAW";
16297 const EXTRA_CRC: u8 = 222u8;
16298 const ENCODED_LEN: usize = 37usize;
16299 fn deser(
16300 _version: MavlinkVersion,
16301 __input: &[u8],
16302 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16303 let avail_len = __input.len();
16304 let mut payload_buf = [0; Self::ENCODED_LEN];
16305 let mut buf = if avail_len < Self::ENCODED_LEN {
16306 payload_buf[0..avail_len].copy_from_slice(__input);
16307 Bytes::new(&payload_buf)
16308 } else {
16309 Bytes::new(__input)
16310 };
16311 let mut __struct = Self::default();
16312 __struct.time_usec = buf.get_u32_le();
16313 __struct.servo1_raw = buf.get_u16_le();
16314 __struct.servo2_raw = buf.get_u16_le();
16315 __struct.servo3_raw = buf.get_u16_le();
16316 __struct.servo4_raw = buf.get_u16_le();
16317 __struct.servo5_raw = buf.get_u16_le();
16318 __struct.servo6_raw = buf.get_u16_le();
16319 __struct.servo7_raw = buf.get_u16_le();
16320 __struct.servo8_raw = buf.get_u16_le();
16321 __struct.port = buf.get_u8();
16322 __struct.servo9_raw = buf.get_u16_le();
16323 __struct.servo10_raw = buf.get_u16_le();
16324 __struct.servo11_raw = buf.get_u16_le();
16325 __struct.servo12_raw = buf.get_u16_le();
16326 __struct.servo13_raw = buf.get_u16_le();
16327 __struct.servo14_raw = buf.get_u16_le();
16328 __struct.servo15_raw = buf.get_u16_le();
16329 __struct.servo16_raw = buf.get_u16_le();
16330 Ok(__struct)
16331 }
16332 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16333 let mut __tmp = BytesMut::new(bytes);
16334 #[allow(clippy::absurd_extreme_comparisons)]
16335 #[allow(unused_comparisons)]
16336 if __tmp.remaining() < Self::ENCODED_LEN {
16337 panic!(
16338 "buffer is too small (need {} bytes, but got {})",
16339 Self::ENCODED_LEN,
16340 __tmp.remaining(),
16341 )
16342 }
16343 __tmp.put_u32_le(self.time_usec);
16344 __tmp.put_u16_le(self.servo1_raw);
16345 __tmp.put_u16_le(self.servo2_raw);
16346 __tmp.put_u16_le(self.servo3_raw);
16347 __tmp.put_u16_le(self.servo4_raw);
16348 __tmp.put_u16_le(self.servo5_raw);
16349 __tmp.put_u16_le(self.servo6_raw);
16350 __tmp.put_u16_le(self.servo7_raw);
16351 __tmp.put_u16_le(self.servo8_raw);
16352 __tmp.put_u8(self.port);
16353 __tmp.put_u16_le(self.servo9_raw);
16354 __tmp.put_u16_le(self.servo10_raw);
16355 __tmp.put_u16_le(self.servo11_raw);
16356 __tmp.put_u16_le(self.servo12_raw);
16357 __tmp.put_u16_le(self.servo13_raw);
16358 __tmp.put_u16_le(self.servo14_raw);
16359 __tmp.put_u16_le(self.servo15_raw);
16360 __tmp.put_u16_le(self.servo16_raw);
16361 if matches!(version, MavlinkVersion::V2) {
16362 let len = __tmp.len();
16363 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16364 } else {
16365 __tmp.len()
16366 }
16367 }
16368}
16369#[doc = "id: 300"]
16370#[doc = "Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly."]
16371#[derive(Debug, Clone, PartialEq)]
16372#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16373#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16374pub struct PROTOCOL_VERSION_DATA {
16375 #[doc = "Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc."]
16376 pub version: u16,
16377 #[doc = "Minimum MAVLink version supported"]
16378 pub min_version: u16,
16379 #[doc = "Maximum MAVLink version supported (set to the same value as version by default)"]
16380 pub max_version: u16,
16381 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
16382 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16383 pub spec_version_hash: [u8; 8],
16384 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
16385 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16386 pub library_version_hash: [u8; 8],
16387}
16388impl PROTOCOL_VERSION_DATA {
16389 pub const ENCODED_LEN: usize = 22usize;
16390 pub const DEFAULT: Self = Self {
16391 version: 0_u16,
16392 min_version: 0_u16,
16393 max_version: 0_u16,
16394 spec_version_hash: [0_u8; 8usize],
16395 library_version_hash: [0_u8; 8usize],
16396 };
16397 #[cfg(feature = "arbitrary")]
16398 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16399 use arbitrary::{Arbitrary, Unstructured};
16400 let mut buf = [0u8; 1024];
16401 rng.fill_bytes(&mut buf);
16402 let mut unstructured = Unstructured::new(&buf);
16403 Self::arbitrary(&mut unstructured).unwrap_or_default()
16404 }
16405}
16406impl Default for PROTOCOL_VERSION_DATA {
16407 fn default() -> Self {
16408 Self::DEFAULT.clone()
16409 }
16410}
16411impl MessageData for PROTOCOL_VERSION_DATA {
16412 type Message = MavMessage;
16413 const ID: u32 = 300u32;
16414 const NAME: &'static str = "PROTOCOL_VERSION";
16415 const EXTRA_CRC: u8 = 217u8;
16416 const ENCODED_LEN: usize = 22usize;
16417 fn deser(
16418 _version: MavlinkVersion,
16419 __input: &[u8],
16420 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16421 let avail_len = __input.len();
16422 let mut payload_buf = [0; Self::ENCODED_LEN];
16423 let mut buf = if avail_len < Self::ENCODED_LEN {
16424 payload_buf[0..avail_len].copy_from_slice(__input);
16425 Bytes::new(&payload_buf)
16426 } else {
16427 Bytes::new(__input)
16428 };
16429 let mut __struct = Self::default();
16430 __struct.version = buf.get_u16_le();
16431 __struct.min_version = buf.get_u16_le();
16432 __struct.max_version = buf.get_u16_le();
16433 for v in &mut __struct.spec_version_hash {
16434 let val = buf.get_u8();
16435 *v = val;
16436 }
16437 for v in &mut __struct.library_version_hash {
16438 let val = buf.get_u8();
16439 *v = val;
16440 }
16441 Ok(__struct)
16442 }
16443 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16444 let mut __tmp = BytesMut::new(bytes);
16445 #[allow(clippy::absurd_extreme_comparisons)]
16446 #[allow(unused_comparisons)]
16447 if __tmp.remaining() < Self::ENCODED_LEN {
16448 panic!(
16449 "buffer is too small (need {} bytes, but got {})",
16450 Self::ENCODED_LEN,
16451 __tmp.remaining(),
16452 )
16453 }
16454 __tmp.put_u16_le(self.version);
16455 __tmp.put_u16_le(self.min_version);
16456 __tmp.put_u16_le(self.max_version);
16457 for val in &self.spec_version_hash {
16458 __tmp.put_u8(*val);
16459 }
16460 for val in &self.library_version_hash {
16461 __tmp.put_u8(*val);
16462 }
16463 if matches!(version, MavlinkVersion::V2) {
16464 let len = __tmp.len();
16465 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16466 } else {
16467 __tmp.len()
16468 }
16469 }
16470}
16471#[doc = "id: 37"]
16472#[doc = "Request a partial list of mission items from the system/component. <https://mavlink.io/en/services/mission.html>. If start and end index are the same, just send one waypoint."]
16473#[derive(Debug, Clone, PartialEq)]
16474#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16475#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16476pub struct MISSION_REQUEST_PARTIAL_LIST_DATA {
16477 #[doc = "Start index"]
16478 pub start_index: i16,
16479 #[doc = "End index, -1 by default (-1: send list to end). Else a valid index of the list"]
16480 pub end_index: i16,
16481 #[doc = "System ID"]
16482 pub target_system: u8,
16483 #[doc = "Component ID"]
16484 pub target_component: u8,
16485 #[doc = "Mission type."]
16486 #[cfg_attr(feature = "serde", serde(default))]
16487 pub mission_type: MavMissionType,
16488}
16489impl MISSION_REQUEST_PARTIAL_LIST_DATA {
16490 pub const ENCODED_LEN: usize = 7usize;
16491 pub const DEFAULT: Self = Self {
16492 start_index: 0_i16,
16493 end_index: 0_i16,
16494 target_system: 0_u8,
16495 target_component: 0_u8,
16496 mission_type: MavMissionType::DEFAULT,
16497 };
16498 #[cfg(feature = "arbitrary")]
16499 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16500 use arbitrary::{Arbitrary, Unstructured};
16501 let mut buf = [0u8; 1024];
16502 rng.fill_bytes(&mut buf);
16503 let mut unstructured = Unstructured::new(&buf);
16504 Self::arbitrary(&mut unstructured).unwrap_or_default()
16505 }
16506}
16507impl Default for MISSION_REQUEST_PARTIAL_LIST_DATA {
16508 fn default() -> Self {
16509 Self::DEFAULT.clone()
16510 }
16511}
16512impl MessageData for MISSION_REQUEST_PARTIAL_LIST_DATA {
16513 type Message = MavMessage;
16514 const ID: u32 = 37u32;
16515 const NAME: &'static str = "MISSION_REQUEST_PARTIAL_LIST";
16516 const EXTRA_CRC: u8 = 212u8;
16517 const ENCODED_LEN: usize = 7usize;
16518 fn deser(
16519 _version: MavlinkVersion,
16520 __input: &[u8],
16521 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16522 let avail_len = __input.len();
16523 let mut payload_buf = [0; Self::ENCODED_LEN];
16524 let mut buf = if avail_len < Self::ENCODED_LEN {
16525 payload_buf[0..avail_len].copy_from_slice(__input);
16526 Bytes::new(&payload_buf)
16527 } else {
16528 Bytes::new(__input)
16529 };
16530 let mut __struct = Self::default();
16531 __struct.start_index = buf.get_i16_le();
16532 __struct.end_index = buf.get_i16_le();
16533 __struct.target_system = buf.get_u8();
16534 __struct.target_component = buf.get_u8();
16535 let tmp = buf.get_u8();
16536 __struct.mission_type =
16537 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16538 enum_type: "MavMissionType",
16539 value: tmp as u32,
16540 })?;
16541 Ok(__struct)
16542 }
16543 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16544 let mut __tmp = BytesMut::new(bytes);
16545 #[allow(clippy::absurd_extreme_comparisons)]
16546 #[allow(unused_comparisons)]
16547 if __tmp.remaining() < Self::ENCODED_LEN {
16548 panic!(
16549 "buffer is too small (need {} bytes, but got {})",
16550 Self::ENCODED_LEN,
16551 __tmp.remaining(),
16552 )
16553 }
16554 __tmp.put_i16_le(self.start_index);
16555 __tmp.put_i16_le(self.end_index);
16556 __tmp.put_u8(self.target_system);
16557 __tmp.put_u8(self.target_component);
16558 __tmp.put_u8(self.mission_type as u8);
16559 if matches!(version, MavlinkVersion::V2) {
16560 let len = __tmp.len();
16561 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16562 } else {
16563 __tmp.len()
16564 }
16565 }
16566}
16567#[doc = "id: 116"]
16568#[doc = "The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units."]
16569#[derive(Debug, Clone, PartialEq)]
16570#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16571#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16572pub struct SCALED_IMU2_DATA {
16573 #[doc = "Timestamp (time since system boot)."]
16574 pub time_boot_ms: u32,
16575 #[doc = "X acceleration"]
16576 pub xacc: i16,
16577 #[doc = "Y acceleration"]
16578 pub yacc: i16,
16579 #[doc = "Z acceleration"]
16580 pub zacc: i16,
16581 #[doc = "Angular speed around X axis"]
16582 pub xgyro: i16,
16583 #[doc = "Angular speed around Y axis"]
16584 pub ygyro: i16,
16585 #[doc = "Angular speed around Z axis"]
16586 pub zgyro: i16,
16587 #[doc = "X Magnetic field"]
16588 pub xmag: i16,
16589 #[doc = "Y Magnetic field"]
16590 pub ymag: i16,
16591 #[doc = "Z Magnetic field"]
16592 pub zmag: i16,
16593 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
16594 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16595 pub temperature: i16,
16596}
16597impl SCALED_IMU2_DATA {
16598 pub const ENCODED_LEN: usize = 24usize;
16599 pub const DEFAULT: Self = Self {
16600 time_boot_ms: 0_u32,
16601 xacc: 0_i16,
16602 yacc: 0_i16,
16603 zacc: 0_i16,
16604 xgyro: 0_i16,
16605 ygyro: 0_i16,
16606 zgyro: 0_i16,
16607 xmag: 0_i16,
16608 ymag: 0_i16,
16609 zmag: 0_i16,
16610 temperature: 0_i16,
16611 };
16612 #[cfg(feature = "arbitrary")]
16613 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16614 use arbitrary::{Arbitrary, Unstructured};
16615 let mut buf = [0u8; 1024];
16616 rng.fill_bytes(&mut buf);
16617 let mut unstructured = Unstructured::new(&buf);
16618 Self::arbitrary(&mut unstructured).unwrap_or_default()
16619 }
16620}
16621impl Default for SCALED_IMU2_DATA {
16622 fn default() -> Self {
16623 Self::DEFAULT.clone()
16624 }
16625}
16626impl MessageData for SCALED_IMU2_DATA {
16627 type Message = MavMessage;
16628 const ID: u32 = 116u32;
16629 const NAME: &'static str = "SCALED_IMU2";
16630 const EXTRA_CRC: u8 = 76u8;
16631 const ENCODED_LEN: usize = 24usize;
16632 fn deser(
16633 _version: MavlinkVersion,
16634 __input: &[u8],
16635 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16636 let avail_len = __input.len();
16637 let mut payload_buf = [0; Self::ENCODED_LEN];
16638 let mut buf = if avail_len < Self::ENCODED_LEN {
16639 payload_buf[0..avail_len].copy_from_slice(__input);
16640 Bytes::new(&payload_buf)
16641 } else {
16642 Bytes::new(__input)
16643 };
16644 let mut __struct = Self::default();
16645 __struct.time_boot_ms = buf.get_u32_le();
16646 __struct.xacc = buf.get_i16_le();
16647 __struct.yacc = buf.get_i16_le();
16648 __struct.zacc = buf.get_i16_le();
16649 __struct.xgyro = buf.get_i16_le();
16650 __struct.ygyro = buf.get_i16_le();
16651 __struct.zgyro = buf.get_i16_le();
16652 __struct.xmag = buf.get_i16_le();
16653 __struct.ymag = buf.get_i16_le();
16654 __struct.zmag = buf.get_i16_le();
16655 __struct.temperature = buf.get_i16_le();
16656 Ok(__struct)
16657 }
16658 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16659 let mut __tmp = BytesMut::new(bytes);
16660 #[allow(clippy::absurd_extreme_comparisons)]
16661 #[allow(unused_comparisons)]
16662 if __tmp.remaining() < Self::ENCODED_LEN {
16663 panic!(
16664 "buffer is too small (need {} bytes, but got {})",
16665 Self::ENCODED_LEN,
16666 __tmp.remaining(),
16667 )
16668 }
16669 __tmp.put_u32_le(self.time_boot_ms);
16670 __tmp.put_i16_le(self.xacc);
16671 __tmp.put_i16_le(self.yacc);
16672 __tmp.put_i16_le(self.zacc);
16673 __tmp.put_i16_le(self.xgyro);
16674 __tmp.put_i16_le(self.ygyro);
16675 __tmp.put_i16_le(self.zgyro);
16676 __tmp.put_i16_le(self.xmag);
16677 __tmp.put_i16_le(self.ymag);
16678 __tmp.put_i16_le(self.zmag);
16679 __tmp.put_i16_le(self.temperature);
16680 if matches!(version, MavlinkVersion::V2) {
16681 let len = __tmp.len();
16682 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16683 } else {
16684 __tmp.len()
16685 }
16686 }
16687}
16688#[doc = "id: 132"]
16689#[doc = "Distance sensor information for an onboard rangefinder."]
16690#[derive(Debug, Clone, PartialEq)]
16691#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16692#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16693pub struct DISTANCE_SENSOR_DATA {
16694 #[doc = "Timestamp (time since system boot)."]
16695 pub time_boot_ms: u32,
16696 #[doc = "Minimum distance the sensor can measure"]
16697 pub min_distance: u16,
16698 #[doc = "Maximum distance the sensor can measure"]
16699 pub max_distance: u16,
16700 #[doc = "Current distance reading"]
16701 pub current_distance: u16,
16702 #[doc = "Type of distance sensor."]
16703 pub mavtype: MavDistanceSensor,
16704 #[doc = "Onboard ID of the sensor"]
16705 pub id: u8,
16706 #[doc = "Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270"]
16707 pub orientation: MavSensorOrientation,
16708 #[doc = "Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown."]
16709 pub covariance: u8,
16710 #[doc = "Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
16711 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16712 pub horizontal_fov: f32,
16713 #[doc = "Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
16714 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16715 pub vertical_fov: f32,
16716 #[doc = "Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.\""]
16717 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16718 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16719 pub quaternion: [f32; 4],
16720 #[doc = "Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal."]
16721 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16722 pub signal_quality: u8,
16723}
16724impl DISTANCE_SENSOR_DATA {
16725 pub const ENCODED_LEN: usize = 39usize;
16726 pub const DEFAULT: Self = Self {
16727 time_boot_ms: 0_u32,
16728 min_distance: 0_u16,
16729 max_distance: 0_u16,
16730 current_distance: 0_u16,
16731 mavtype: MavDistanceSensor::DEFAULT,
16732 id: 0_u8,
16733 orientation: MavSensorOrientation::DEFAULT,
16734 covariance: 0_u8,
16735 horizontal_fov: 0.0_f32,
16736 vertical_fov: 0.0_f32,
16737 quaternion: [0.0_f32; 4usize],
16738 signal_quality: 0_u8,
16739 };
16740 #[cfg(feature = "arbitrary")]
16741 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16742 use arbitrary::{Arbitrary, Unstructured};
16743 let mut buf = [0u8; 1024];
16744 rng.fill_bytes(&mut buf);
16745 let mut unstructured = Unstructured::new(&buf);
16746 Self::arbitrary(&mut unstructured).unwrap_or_default()
16747 }
16748}
16749impl Default for DISTANCE_SENSOR_DATA {
16750 fn default() -> Self {
16751 Self::DEFAULT.clone()
16752 }
16753}
16754impl MessageData for DISTANCE_SENSOR_DATA {
16755 type Message = MavMessage;
16756 const ID: u32 = 132u32;
16757 const NAME: &'static str = "DISTANCE_SENSOR";
16758 const EXTRA_CRC: u8 = 85u8;
16759 const ENCODED_LEN: usize = 39usize;
16760 fn deser(
16761 _version: MavlinkVersion,
16762 __input: &[u8],
16763 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16764 let avail_len = __input.len();
16765 let mut payload_buf = [0; Self::ENCODED_LEN];
16766 let mut buf = if avail_len < Self::ENCODED_LEN {
16767 payload_buf[0..avail_len].copy_from_slice(__input);
16768 Bytes::new(&payload_buf)
16769 } else {
16770 Bytes::new(__input)
16771 };
16772 let mut __struct = Self::default();
16773 __struct.time_boot_ms = buf.get_u32_le();
16774 __struct.min_distance = buf.get_u16_le();
16775 __struct.max_distance = buf.get_u16_le();
16776 __struct.current_distance = buf.get_u16_le();
16777 let tmp = buf.get_u8();
16778 __struct.mavtype =
16779 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16780 enum_type: "MavDistanceSensor",
16781 value: tmp as u32,
16782 })?;
16783 __struct.id = buf.get_u8();
16784 let tmp = buf.get_u8();
16785 __struct.orientation =
16786 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16787 enum_type: "MavSensorOrientation",
16788 value: tmp as u32,
16789 })?;
16790 __struct.covariance = buf.get_u8();
16791 __struct.horizontal_fov = buf.get_f32_le();
16792 __struct.vertical_fov = buf.get_f32_le();
16793 for v in &mut __struct.quaternion {
16794 let val = buf.get_f32_le();
16795 *v = val;
16796 }
16797 __struct.signal_quality = buf.get_u8();
16798 Ok(__struct)
16799 }
16800 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16801 let mut __tmp = BytesMut::new(bytes);
16802 #[allow(clippy::absurd_extreme_comparisons)]
16803 #[allow(unused_comparisons)]
16804 if __tmp.remaining() < Self::ENCODED_LEN {
16805 panic!(
16806 "buffer is too small (need {} bytes, but got {})",
16807 Self::ENCODED_LEN,
16808 __tmp.remaining(),
16809 )
16810 }
16811 __tmp.put_u32_le(self.time_boot_ms);
16812 __tmp.put_u16_le(self.min_distance);
16813 __tmp.put_u16_le(self.max_distance);
16814 __tmp.put_u16_le(self.current_distance);
16815 __tmp.put_u8(self.mavtype as u8);
16816 __tmp.put_u8(self.id);
16817 __tmp.put_u8(self.orientation as u8);
16818 __tmp.put_u8(self.covariance);
16819 __tmp.put_f32_le(self.horizontal_fov);
16820 __tmp.put_f32_le(self.vertical_fov);
16821 for val in &self.quaternion {
16822 __tmp.put_f32_le(*val);
16823 }
16824 __tmp.put_u8(self.signal_quality);
16825 if matches!(version, MavlinkVersion::V2) {
16826 let len = __tmp.len();
16827 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16828 } else {
16829 __tmp.len()
16830 }
16831 }
16832}
16833#[doc = "id: 48"]
16834#[doc = "Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor."]
16835#[derive(Debug, Clone, PartialEq)]
16836#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16837#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16838pub struct SET_GPS_GLOBAL_ORIGIN_DATA {
16839 #[doc = "Latitude (WGS84)"]
16840 pub latitude: i32,
16841 #[doc = "Longitude (WGS84)"]
16842 pub longitude: i32,
16843 #[doc = "Altitude (MSL). Positive for up."]
16844 pub altitude: i32,
16845 #[doc = "System ID"]
16846 pub target_system: u8,
16847 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16848 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16849 pub time_usec: u64,
16850}
16851impl SET_GPS_GLOBAL_ORIGIN_DATA {
16852 pub const ENCODED_LEN: usize = 21usize;
16853 pub const DEFAULT: Self = Self {
16854 latitude: 0_i32,
16855 longitude: 0_i32,
16856 altitude: 0_i32,
16857 target_system: 0_u8,
16858 time_usec: 0_u64,
16859 };
16860 #[cfg(feature = "arbitrary")]
16861 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16862 use arbitrary::{Arbitrary, Unstructured};
16863 let mut buf = [0u8; 1024];
16864 rng.fill_bytes(&mut buf);
16865 let mut unstructured = Unstructured::new(&buf);
16866 Self::arbitrary(&mut unstructured).unwrap_or_default()
16867 }
16868}
16869impl Default for SET_GPS_GLOBAL_ORIGIN_DATA {
16870 fn default() -> Self {
16871 Self::DEFAULT.clone()
16872 }
16873}
16874impl MessageData for SET_GPS_GLOBAL_ORIGIN_DATA {
16875 type Message = MavMessage;
16876 const ID: u32 = 48u32;
16877 const NAME: &'static str = "SET_GPS_GLOBAL_ORIGIN";
16878 const EXTRA_CRC: u8 = 41u8;
16879 const ENCODED_LEN: usize = 21usize;
16880 fn deser(
16881 _version: MavlinkVersion,
16882 __input: &[u8],
16883 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16884 let avail_len = __input.len();
16885 let mut payload_buf = [0; Self::ENCODED_LEN];
16886 let mut buf = if avail_len < Self::ENCODED_LEN {
16887 payload_buf[0..avail_len].copy_from_slice(__input);
16888 Bytes::new(&payload_buf)
16889 } else {
16890 Bytes::new(__input)
16891 };
16892 let mut __struct = Self::default();
16893 __struct.latitude = buf.get_i32_le();
16894 __struct.longitude = buf.get_i32_le();
16895 __struct.altitude = buf.get_i32_le();
16896 __struct.target_system = buf.get_u8();
16897 __struct.time_usec = buf.get_u64_le();
16898 Ok(__struct)
16899 }
16900 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16901 let mut __tmp = BytesMut::new(bytes);
16902 #[allow(clippy::absurd_extreme_comparisons)]
16903 #[allow(unused_comparisons)]
16904 if __tmp.remaining() < Self::ENCODED_LEN {
16905 panic!(
16906 "buffer is too small (need {} bytes, but got {})",
16907 Self::ENCODED_LEN,
16908 __tmp.remaining(),
16909 )
16910 }
16911 __tmp.put_i32_le(self.latitude);
16912 __tmp.put_i32_le(self.longitude);
16913 __tmp.put_i32_le(self.altitude);
16914 __tmp.put_u8(self.target_system);
16915 __tmp.put_u64_le(self.time_usec);
16916 if matches!(version, MavlinkVersion::V2) {
16917 let len = __tmp.len();
16918 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16919 } else {
16920 __tmp.len()
16921 }
16922 }
16923}
16924#[doc = "id: 335"]
16925#[doc = "Status of the Iridium SBD link."]
16926#[derive(Debug, Clone, PartialEq)]
16927#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16928#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16929pub struct ISBD_LINK_STATUS_DATA {
16930 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16931 pub timestamp: u64,
16932 #[doc = "Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16933 pub last_heartbeat: u64,
16934 #[doc = "Number of failed SBD sessions."]
16935 pub failed_sessions: u16,
16936 #[doc = "Number of successful SBD sessions."]
16937 pub successful_sessions: u16,
16938 #[doc = "Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength."]
16939 pub signal_quality: u8,
16940 #[doc = "1: Ring call pending, 0: No call pending."]
16941 pub ring_pending: u8,
16942 #[doc = "1: Transmission session pending, 0: No transmission session pending."]
16943 pub tx_session_pending: u8,
16944 #[doc = "1: Receiving session pending, 0: No receiving session pending."]
16945 pub rx_session_pending: u8,
16946}
16947impl ISBD_LINK_STATUS_DATA {
16948 pub const ENCODED_LEN: usize = 24usize;
16949 pub const DEFAULT: Self = Self {
16950 timestamp: 0_u64,
16951 last_heartbeat: 0_u64,
16952 failed_sessions: 0_u16,
16953 successful_sessions: 0_u16,
16954 signal_quality: 0_u8,
16955 ring_pending: 0_u8,
16956 tx_session_pending: 0_u8,
16957 rx_session_pending: 0_u8,
16958 };
16959 #[cfg(feature = "arbitrary")]
16960 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16961 use arbitrary::{Arbitrary, Unstructured};
16962 let mut buf = [0u8; 1024];
16963 rng.fill_bytes(&mut buf);
16964 let mut unstructured = Unstructured::new(&buf);
16965 Self::arbitrary(&mut unstructured).unwrap_or_default()
16966 }
16967}
16968impl Default for ISBD_LINK_STATUS_DATA {
16969 fn default() -> Self {
16970 Self::DEFAULT.clone()
16971 }
16972}
16973impl MessageData for ISBD_LINK_STATUS_DATA {
16974 type Message = MavMessage;
16975 const ID: u32 = 335u32;
16976 const NAME: &'static str = "ISBD_LINK_STATUS";
16977 const EXTRA_CRC: u8 = 225u8;
16978 const ENCODED_LEN: usize = 24usize;
16979 fn deser(
16980 _version: MavlinkVersion,
16981 __input: &[u8],
16982 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16983 let avail_len = __input.len();
16984 let mut payload_buf = [0; Self::ENCODED_LEN];
16985 let mut buf = if avail_len < Self::ENCODED_LEN {
16986 payload_buf[0..avail_len].copy_from_slice(__input);
16987 Bytes::new(&payload_buf)
16988 } else {
16989 Bytes::new(__input)
16990 };
16991 let mut __struct = Self::default();
16992 __struct.timestamp = buf.get_u64_le();
16993 __struct.last_heartbeat = buf.get_u64_le();
16994 __struct.failed_sessions = buf.get_u16_le();
16995 __struct.successful_sessions = buf.get_u16_le();
16996 __struct.signal_quality = buf.get_u8();
16997 __struct.ring_pending = buf.get_u8();
16998 __struct.tx_session_pending = buf.get_u8();
16999 __struct.rx_session_pending = buf.get_u8();
17000 Ok(__struct)
17001 }
17002 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17003 let mut __tmp = BytesMut::new(bytes);
17004 #[allow(clippy::absurd_extreme_comparisons)]
17005 #[allow(unused_comparisons)]
17006 if __tmp.remaining() < Self::ENCODED_LEN {
17007 panic!(
17008 "buffer is too small (need {} bytes, but got {})",
17009 Self::ENCODED_LEN,
17010 __tmp.remaining(),
17011 )
17012 }
17013 __tmp.put_u64_le(self.timestamp);
17014 __tmp.put_u64_le(self.last_heartbeat);
17015 __tmp.put_u16_le(self.failed_sessions);
17016 __tmp.put_u16_le(self.successful_sessions);
17017 __tmp.put_u8(self.signal_quality);
17018 __tmp.put_u8(self.ring_pending);
17019 __tmp.put_u8(self.tx_session_pending);
17020 __tmp.put_u8(self.rx_session_pending);
17021 if matches!(version, MavlinkVersion::V2) {
17022 let len = __tmp.len();
17023 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17024 } else {
17025 __tmp.len()
17026 }
17027 }
17028}
17029#[doc = "id: 410"]
17030#[doc = "Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component)."]
17031#[derive(Debug, Clone, PartialEq)]
17032#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17033#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17034pub struct EVENT_DATA {
17035 #[doc = "Event ID (as defined in the component metadata)"]
17036 pub id: u32,
17037 #[doc = "Timestamp (time since system boot when the event happened)."]
17038 pub event_time_boot_ms: u32,
17039 #[doc = "Sequence number."]
17040 pub sequence: u16,
17041 #[doc = "Component ID"]
17042 pub destination_component: u8,
17043 #[doc = "System ID"]
17044 pub destination_system: u8,
17045 #[doc = "Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9"]
17046 pub log_levels: u8,
17047 #[doc = "Arguments (depend on event ID)."]
17048 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17049 pub arguments: [u8; 40],
17050}
17051impl EVENT_DATA {
17052 pub const ENCODED_LEN: usize = 53usize;
17053 pub const DEFAULT: Self = Self {
17054 id: 0_u32,
17055 event_time_boot_ms: 0_u32,
17056 sequence: 0_u16,
17057 destination_component: 0_u8,
17058 destination_system: 0_u8,
17059 log_levels: 0_u8,
17060 arguments: [0_u8; 40usize],
17061 };
17062 #[cfg(feature = "arbitrary")]
17063 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17064 use arbitrary::{Arbitrary, Unstructured};
17065 let mut buf = [0u8; 1024];
17066 rng.fill_bytes(&mut buf);
17067 let mut unstructured = Unstructured::new(&buf);
17068 Self::arbitrary(&mut unstructured).unwrap_or_default()
17069 }
17070}
17071impl Default for EVENT_DATA {
17072 fn default() -> Self {
17073 Self::DEFAULT.clone()
17074 }
17075}
17076impl MessageData for EVENT_DATA {
17077 type Message = MavMessage;
17078 const ID: u32 = 410u32;
17079 const NAME: &'static str = "EVENT";
17080 const EXTRA_CRC: u8 = 160u8;
17081 const ENCODED_LEN: usize = 53usize;
17082 fn deser(
17083 _version: MavlinkVersion,
17084 __input: &[u8],
17085 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17086 let avail_len = __input.len();
17087 let mut payload_buf = [0; Self::ENCODED_LEN];
17088 let mut buf = if avail_len < Self::ENCODED_LEN {
17089 payload_buf[0..avail_len].copy_from_slice(__input);
17090 Bytes::new(&payload_buf)
17091 } else {
17092 Bytes::new(__input)
17093 };
17094 let mut __struct = Self::default();
17095 __struct.id = buf.get_u32_le();
17096 __struct.event_time_boot_ms = buf.get_u32_le();
17097 __struct.sequence = buf.get_u16_le();
17098 __struct.destination_component = buf.get_u8();
17099 __struct.destination_system = buf.get_u8();
17100 __struct.log_levels = buf.get_u8();
17101 for v in &mut __struct.arguments {
17102 let val = buf.get_u8();
17103 *v = val;
17104 }
17105 Ok(__struct)
17106 }
17107 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17108 let mut __tmp = BytesMut::new(bytes);
17109 #[allow(clippy::absurd_extreme_comparisons)]
17110 #[allow(unused_comparisons)]
17111 if __tmp.remaining() < Self::ENCODED_LEN {
17112 panic!(
17113 "buffer is too small (need {} bytes, but got {})",
17114 Self::ENCODED_LEN,
17115 __tmp.remaining(),
17116 )
17117 }
17118 __tmp.put_u32_le(self.id);
17119 __tmp.put_u32_le(self.event_time_boot_ms);
17120 __tmp.put_u16_le(self.sequence);
17121 __tmp.put_u8(self.destination_component);
17122 __tmp.put_u8(self.destination_system);
17123 __tmp.put_u8(self.log_levels);
17124 for val in &self.arguments {
17125 __tmp.put_u8(*val);
17126 }
17127 if matches!(version, MavlinkVersion::V2) {
17128 let len = __tmp.len();
17129 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17130 } else {
17131 __tmp.len()
17132 }
17133 }
17134}
17135#[doc = "id: 281"]
17136#[doc = "Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz)."]
17137#[derive(Debug, Clone, PartialEq)]
17138#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17139#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17140pub struct GIMBAL_MANAGER_STATUS_DATA {
17141 #[doc = "Timestamp (time since system boot)."]
17142 pub time_boot_ms: u32,
17143 #[doc = "High level gimbal manager flags currently applied."]
17144 pub flags: GimbalManagerFlags,
17145 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
17146 pub gimbal_device_id: u8,
17147 #[doc = "System ID of MAVLink component with primary control, 0 for none."]
17148 pub primary_control_sysid: u8,
17149 #[doc = "Component ID of MAVLink component with primary control, 0 for none."]
17150 pub primary_control_compid: u8,
17151 #[doc = "System ID of MAVLink component with secondary control, 0 for none."]
17152 pub secondary_control_sysid: u8,
17153 #[doc = "Component ID of MAVLink component with secondary control, 0 for none."]
17154 pub secondary_control_compid: u8,
17155}
17156impl GIMBAL_MANAGER_STATUS_DATA {
17157 pub const ENCODED_LEN: usize = 13usize;
17158 pub const DEFAULT: Self = Self {
17159 time_boot_ms: 0_u32,
17160 flags: GimbalManagerFlags::DEFAULT,
17161 gimbal_device_id: 0_u8,
17162 primary_control_sysid: 0_u8,
17163 primary_control_compid: 0_u8,
17164 secondary_control_sysid: 0_u8,
17165 secondary_control_compid: 0_u8,
17166 };
17167 #[cfg(feature = "arbitrary")]
17168 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17169 use arbitrary::{Arbitrary, Unstructured};
17170 let mut buf = [0u8; 1024];
17171 rng.fill_bytes(&mut buf);
17172 let mut unstructured = Unstructured::new(&buf);
17173 Self::arbitrary(&mut unstructured).unwrap_or_default()
17174 }
17175}
17176impl Default for GIMBAL_MANAGER_STATUS_DATA {
17177 fn default() -> Self {
17178 Self::DEFAULT.clone()
17179 }
17180}
17181impl MessageData for GIMBAL_MANAGER_STATUS_DATA {
17182 type Message = MavMessage;
17183 const ID: u32 = 281u32;
17184 const NAME: &'static str = "GIMBAL_MANAGER_STATUS";
17185 const EXTRA_CRC: u8 = 48u8;
17186 const ENCODED_LEN: usize = 13usize;
17187 fn deser(
17188 _version: MavlinkVersion,
17189 __input: &[u8],
17190 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17191 let avail_len = __input.len();
17192 let mut payload_buf = [0; Self::ENCODED_LEN];
17193 let mut buf = if avail_len < Self::ENCODED_LEN {
17194 payload_buf[0..avail_len].copy_from_slice(__input);
17195 Bytes::new(&payload_buf)
17196 } else {
17197 Bytes::new(__input)
17198 };
17199 let mut __struct = Self::default();
17200 __struct.time_boot_ms = buf.get_u32_le();
17201 let tmp = buf.get_u32_le();
17202 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
17203 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
17204 flag_type: "GimbalManagerFlags",
17205 value: tmp as u32,
17206 })?;
17207 __struct.gimbal_device_id = buf.get_u8();
17208 __struct.primary_control_sysid = buf.get_u8();
17209 __struct.primary_control_compid = buf.get_u8();
17210 __struct.secondary_control_sysid = buf.get_u8();
17211 __struct.secondary_control_compid = buf.get_u8();
17212 Ok(__struct)
17213 }
17214 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17215 let mut __tmp = BytesMut::new(bytes);
17216 #[allow(clippy::absurd_extreme_comparisons)]
17217 #[allow(unused_comparisons)]
17218 if __tmp.remaining() < Self::ENCODED_LEN {
17219 panic!(
17220 "buffer is too small (need {} bytes, but got {})",
17221 Self::ENCODED_LEN,
17222 __tmp.remaining(),
17223 )
17224 }
17225 __tmp.put_u32_le(self.time_boot_ms);
17226 __tmp.put_u32_le(self.flags.bits());
17227 __tmp.put_u8(self.gimbal_device_id);
17228 __tmp.put_u8(self.primary_control_sysid);
17229 __tmp.put_u8(self.primary_control_compid);
17230 __tmp.put_u8(self.secondary_control_sysid);
17231 __tmp.put_u8(self.secondary_control_compid);
17232 if matches!(version, MavlinkVersion::V2) {
17233 let len = __tmp.len();
17234 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17235 } else {
17236 __tmp.len()
17237 }
17238 }
17239}
17240#[doc = "id: 20"]
17241#[doc = "value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also <https://mavlink.io/en/services/parameter.html> for a full documentation of QGroundControl and IMU code."]
17242#[derive(Debug, Clone, PartialEq)]
17243#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17244#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17245pub struct PARAM_REQUEST_READ_DATA {
17246 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)"]
17247 pub param_index: i16,
17248 #[doc = "System ID"]
17249 pub target_system: u8,
17250 #[doc = "Component ID"]
17251 pub target_component: u8,
17252 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
17253 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17254 pub param_id: [u8; 16],
17255}
17256impl PARAM_REQUEST_READ_DATA {
17257 pub const ENCODED_LEN: usize = 20usize;
17258 pub const DEFAULT: Self = Self {
17259 param_index: 0_i16,
17260 target_system: 0_u8,
17261 target_component: 0_u8,
17262 param_id: [0_u8; 16usize],
17263 };
17264 #[cfg(feature = "arbitrary")]
17265 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17266 use arbitrary::{Arbitrary, Unstructured};
17267 let mut buf = [0u8; 1024];
17268 rng.fill_bytes(&mut buf);
17269 let mut unstructured = Unstructured::new(&buf);
17270 Self::arbitrary(&mut unstructured).unwrap_or_default()
17271 }
17272}
17273impl Default for PARAM_REQUEST_READ_DATA {
17274 fn default() -> Self {
17275 Self::DEFAULT.clone()
17276 }
17277}
17278impl MessageData for PARAM_REQUEST_READ_DATA {
17279 type Message = MavMessage;
17280 const ID: u32 = 20u32;
17281 const NAME: &'static str = "PARAM_REQUEST_READ";
17282 const EXTRA_CRC: u8 = 214u8;
17283 const ENCODED_LEN: usize = 20usize;
17284 fn deser(
17285 _version: MavlinkVersion,
17286 __input: &[u8],
17287 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17288 let avail_len = __input.len();
17289 let mut payload_buf = [0; Self::ENCODED_LEN];
17290 let mut buf = if avail_len < Self::ENCODED_LEN {
17291 payload_buf[0..avail_len].copy_from_slice(__input);
17292 Bytes::new(&payload_buf)
17293 } else {
17294 Bytes::new(__input)
17295 };
17296 let mut __struct = Self::default();
17297 __struct.param_index = buf.get_i16_le();
17298 __struct.target_system = buf.get_u8();
17299 __struct.target_component = buf.get_u8();
17300 for v in &mut __struct.param_id {
17301 let val = buf.get_u8();
17302 *v = val;
17303 }
17304 Ok(__struct)
17305 }
17306 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17307 let mut __tmp = BytesMut::new(bytes);
17308 #[allow(clippy::absurd_extreme_comparisons)]
17309 #[allow(unused_comparisons)]
17310 if __tmp.remaining() < Self::ENCODED_LEN {
17311 panic!(
17312 "buffer is too small (need {} bytes, but got {})",
17313 Self::ENCODED_LEN,
17314 __tmp.remaining(),
17315 )
17316 }
17317 __tmp.put_i16_le(self.param_index);
17318 __tmp.put_u8(self.target_system);
17319 __tmp.put_u8(self.target_component);
17320 for val in &self.param_id {
17321 __tmp.put_u8(*val);
17322 }
17323 if matches!(version, MavlinkVersion::V2) {
17324 let len = __tmp.len();
17325 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17326 } else {
17327 __tmp.len()
17328 }
17329 }
17330}
17331#[doc = "id: 253"]
17332#[doc = "Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz)."]
17333#[derive(Debug, Clone, PartialEq)]
17334#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17335#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17336pub struct STATUSTEXT_DATA {
17337 #[doc = "Severity of status. Relies on the definitions within RFC-5424."]
17338 pub severity: MavSeverity,
17339 #[doc = "Status text message, without null termination character"]
17340 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17341 pub text: [u8; 50],
17342 #[doc = "Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately."]
17343 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17344 pub id: u16,
17345 #[doc = "This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk."]
17346 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17347 pub chunk_seq: u8,
17348}
17349impl STATUSTEXT_DATA {
17350 pub const ENCODED_LEN: usize = 54usize;
17351 pub const DEFAULT: Self = Self {
17352 severity: MavSeverity::DEFAULT,
17353 text: [0_u8; 50usize],
17354 id: 0_u16,
17355 chunk_seq: 0_u8,
17356 };
17357 #[cfg(feature = "arbitrary")]
17358 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17359 use arbitrary::{Arbitrary, Unstructured};
17360 let mut buf = [0u8; 1024];
17361 rng.fill_bytes(&mut buf);
17362 let mut unstructured = Unstructured::new(&buf);
17363 Self::arbitrary(&mut unstructured).unwrap_or_default()
17364 }
17365}
17366impl Default for STATUSTEXT_DATA {
17367 fn default() -> Self {
17368 Self::DEFAULT.clone()
17369 }
17370}
17371impl MessageData for STATUSTEXT_DATA {
17372 type Message = MavMessage;
17373 const ID: u32 = 253u32;
17374 const NAME: &'static str = "STATUSTEXT";
17375 const EXTRA_CRC: u8 = 83u8;
17376 const ENCODED_LEN: usize = 54usize;
17377 fn deser(
17378 _version: MavlinkVersion,
17379 __input: &[u8],
17380 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17381 let avail_len = __input.len();
17382 let mut payload_buf = [0; Self::ENCODED_LEN];
17383 let mut buf = if avail_len < Self::ENCODED_LEN {
17384 payload_buf[0..avail_len].copy_from_slice(__input);
17385 Bytes::new(&payload_buf)
17386 } else {
17387 Bytes::new(__input)
17388 };
17389 let mut __struct = Self::default();
17390 let tmp = buf.get_u8();
17391 __struct.severity =
17392 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17393 enum_type: "MavSeverity",
17394 value: tmp as u32,
17395 })?;
17396 for v in &mut __struct.text {
17397 let val = buf.get_u8();
17398 *v = val;
17399 }
17400 __struct.id = buf.get_u16_le();
17401 __struct.chunk_seq = buf.get_u8();
17402 Ok(__struct)
17403 }
17404 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17405 let mut __tmp = BytesMut::new(bytes);
17406 #[allow(clippy::absurd_extreme_comparisons)]
17407 #[allow(unused_comparisons)]
17408 if __tmp.remaining() < Self::ENCODED_LEN {
17409 panic!(
17410 "buffer is too small (need {} bytes, but got {})",
17411 Self::ENCODED_LEN,
17412 __tmp.remaining(),
17413 )
17414 }
17415 __tmp.put_u8(self.severity as u8);
17416 for val in &self.text {
17417 __tmp.put_u8(*val);
17418 }
17419 __tmp.put_u16_le(self.id);
17420 __tmp.put_u8(self.chunk_seq);
17421 if matches!(version, MavlinkVersion::V2) {
17422 let len = __tmp.len();
17423 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17424 } else {
17425 __tmp.len()
17426 }
17427 }
17428}
17429#[doc = "id: 5"]
17430#[doc = "Request to control this MAV."]
17431#[derive(Debug, Clone, PartialEq)]
17432#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17433#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17434pub struct CHANGE_OPERATOR_CONTROL_DATA {
17435 #[doc = "System the GCS requests control for"]
17436 pub target_system: u8,
17437 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
17438 pub control_request: u8,
17439 #[doc = "0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch."]
17440 pub version: u8,
17441 #[doc = "Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and \"!?,.-\""]
17442 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17443 pub passkey: [u8; 25],
17444}
17445impl CHANGE_OPERATOR_CONTROL_DATA {
17446 pub const ENCODED_LEN: usize = 28usize;
17447 pub const DEFAULT: Self = Self {
17448 target_system: 0_u8,
17449 control_request: 0_u8,
17450 version: 0_u8,
17451 passkey: [0_u8; 25usize],
17452 };
17453 #[cfg(feature = "arbitrary")]
17454 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17455 use arbitrary::{Arbitrary, Unstructured};
17456 let mut buf = [0u8; 1024];
17457 rng.fill_bytes(&mut buf);
17458 let mut unstructured = Unstructured::new(&buf);
17459 Self::arbitrary(&mut unstructured).unwrap_or_default()
17460 }
17461}
17462impl Default for CHANGE_OPERATOR_CONTROL_DATA {
17463 fn default() -> Self {
17464 Self::DEFAULT.clone()
17465 }
17466}
17467impl MessageData for CHANGE_OPERATOR_CONTROL_DATA {
17468 type Message = MavMessage;
17469 const ID: u32 = 5u32;
17470 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL";
17471 const EXTRA_CRC: u8 = 217u8;
17472 const ENCODED_LEN: usize = 28usize;
17473 fn deser(
17474 _version: MavlinkVersion,
17475 __input: &[u8],
17476 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17477 let avail_len = __input.len();
17478 let mut payload_buf = [0; Self::ENCODED_LEN];
17479 let mut buf = if avail_len < Self::ENCODED_LEN {
17480 payload_buf[0..avail_len].copy_from_slice(__input);
17481 Bytes::new(&payload_buf)
17482 } else {
17483 Bytes::new(__input)
17484 };
17485 let mut __struct = Self::default();
17486 __struct.target_system = buf.get_u8();
17487 __struct.control_request = buf.get_u8();
17488 __struct.version = buf.get_u8();
17489 for v in &mut __struct.passkey {
17490 let val = buf.get_u8();
17491 *v = val;
17492 }
17493 Ok(__struct)
17494 }
17495 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17496 let mut __tmp = BytesMut::new(bytes);
17497 #[allow(clippy::absurd_extreme_comparisons)]
17498 #[allow(unused_comparisons)]
17499 if __tmp.remaining() < Self::ENCODED_LEN {
17500 panic!(
17501 "buffer is too small (need {} bytes, but got {})",
17502 Self::ENCODED_LEN,
17503 __tmp.remaining(),
17504 )
17505 }
17506 __tmp.put_u8(self.target_system);
17507 __tmp.put_u8(self.control_request);
17508 __tmp.put_u8(self.version);
17509 for val in &self.passkey {
17510 __tmp.put_u8(*val);
17511 }
17512 if matches!(version, MavlinkVersion::V2) {
17513 let len = __tmp.len();
17514 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17515 } else {
17516 __tmp.len()
17517 }
17518 }
17519}
17520#[doc = "id: 225"]
17521#[doc = "EFI status output."]
17522#[derive(Debug, Clone, PartialEq)]
17523#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17524#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17525pub struct EFI_STATUS_DATA {
17526 #[doc = "ECU index"]
17527 pub ecu_index: f32,
17528 #[doc = "RPM"]
17529 pub rpm: f32,
17530 #[doc = "Fuel consumed"]
17531 pub fuel_consumed: f32,
17532 #[doc = "Fuel flow rate"]
17533 pub fuel_flow: f32,
17534 #[doc = "Engine load"]
17535 pub engine_load: f32,
17536 #[doc = "Throttle position"]
17537 pub throttle_position: f32,
17538 #[doc = "Spark dwell time"]
17539 pub spark_dwell_time: f32,
17540 #[doc = "Barometric pressure"]
17541 pub barometric_pressure: f32,
17542 #[doc = "Intake manifold pressure("]
17543 pub intake_manifold_pressure: f32,
17544 #[doc = "Intake manifold temperature"]
17545 pub intake_manifold_temperature: f32,
17546 #[doc = "Cylinder head temperature"]
17547 pub cylinder_head_temperature: f32,
17548 #[doc = "Ignition timing (Crank angle degrees)"]
17549 pub ignition_timing: f32,
17550 #[doc = "Injection time"]
17551 pub injection_time: f32,
17552 #[doc = "Exhaust gas temperature"]
17553 pub exhaust_gas_temperature: f32,
17554 #[doc = "Output throttle"]
17555 pub throttle_out: f32,
17556 #[doc = "Pressure/temperature compensation"]
17557 pub pt_compensation: f32,
17558 #[doc = "EFI health status"]
17559 pub health: u8,
17560 #[doc = "Supply voltage to EFI sparking system. Zero in this value means \"unknown\", so if the supply voltage really is zero volts use 0.0001 instead."]
17561 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17562 pub ignition_voltage: f32,
17563 #[doc = "Fuel pressure. Zero in this value means \"unknown\", so if the fuel pressure really is zero kPa use 0.0001 instead."]
17564 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17565 pub fuel_pressure: f32,
17566}
17567impl EFI_STATUS_DATA {
17568 pub const ENCODED_LEN: usize = 73usize;
17569 pub const DEFAULT: Self = Self {
17570 ecu_index: 0.0_f32,
17571 rpm: 0.0_f32,
17572 fuel_consumed: 0.0_f32,
17573 fuel_flow: 0.0_f32,
17574 engine_load: 0.0_f32,
17575 throttle_position: 0.0_f32,
17576 spark_dwell_time: 0.0_f32,
17577 barometric_pressure: 0.0_f32,
17578 intake_manifold_pressure: 0.0_f32,
17579 intake_manifold_temperature: 0.0_f32,
17580 cylinder_head_temperature: 0.0_f32,
17581 ignition_timing: 0.0_f32,
17582 injection_time: 0.0_f32,
17583 exhaust_gas_temperature: 0.0_f32,
17584 throttle_out: 0.0_f32,
17585 pt_compensation: 0.0_f32,
17586 health: 0_u8,
17587 ignition_voltage: 0.0_f32,
17588 fuel_pressure: 0.0_f32,
17589 };
17590 #[cfg(feature = "arbitrary")]
17591 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17592 use arbitrary::{Arbitrary, Unstructured};
17593 let mut buf = [0u8; 1024];
17594 rng.fill_bytes(&mut buf);
17595 let mut unstructured = Unstructured::new(&buf);
17596 Self::arbitrary(&mut unstructured).unwrap_or_default()
17597 }
17598}
17599impl Default for EFI_STATUS_DATA {
17600 fn default() -> Self {
17601 Self::DEFAULT.clone()
17602 }
17603}
17604impl MessageData for EFI_STATUS_DATA {
17605 type Message = MavMessage;
17606 const ID: u32 = 225u32;
17607 const NAME: &'static str = "EFI_STATUS";
17608 const EXTRA_CRC: u8 = 208u8;
17609 const ENCODED_LEN: usize = 73usize;
17610 fn deser(
17611 _version: MavlinkVersion,
17612 __input: &[u8],
17613 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17614 let avail_len = __input.len();
17615 let mut payload_buf = [0; Self::ENCODED_LEN];
17616 let mut buf = if avail_len < Self::ENCODED_LEN {
17617 payload_buf[0..avail_len].copy_from_slice(__input);
17618 Bytes::new(&payload_buf)
17619 } else {
17620 Bytes::new(__input)
17621 };
17622 let mut __struct = Self::default();
17623 __struct.ecu_index = buf.get_f32_le();
17624 __struct.rpm = buf.get_f32_le();
17625 __struct.fuel_consumed = buf.get_f32_le();
17626 __struct.fuel_flow = buf.get_f32_le();
17627 __struct.engine_load = buf.get_f32_le();
17628 __struct.throttle_position = buf.get_f32_le();
17629 __struct.spark_dwell_time = buf.get_f32_le();
17630 __struct.barometric_pressure = buf.get_f32_le();
17631 __struct.intake_manifold_pressure = buf.get_f32_le();
17632 __struct.intake_manifold_temperature = buf.get_f32_le();
17633 __struct.cylinder_head_temperature = buf.get_f32_le();
17634 __struct.ignition_timing = buf.get_f32_le();
17635 __struct.injection_time = buf.get_f32_le();
17636 __struct.exhaust_gas_temperature = buf.get_f32_le();
17637 __struct.throttle_out = buf.get_f32_le();
17638 __struct.pt_compensation = buf.get_f32_le();
17639 __struct.health = buf.get_u8();
17640 __struct.ignition_voltage = buf.get_f32_le();
17641 __struct.fuel_pressure = buf.get_f32_le();
17642 Ok(__struct)
17643 }
17644 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17645 let mut __tmp = BytesMut::new(bytes);
17646 #[allow(clippy::absurd_extreme_comparisons)]
17647 #[allow(unused_comparisons)]
17648 if __tmp.remaining() < Self::ENCODED_LEN {
17649 panic!(
17650 "buffer is too small (need {} bytes, but got {})",
17651 Self::ENCODED_LEN,
17652 __tmp.remaining(),
17653 )
17654 }
17655 __tmp.put_f32_le(self.ecu_index);
17656 __tmp.put_f32_le(self.rpm);
17657 __tmp.put_f32_le(self.fuel_consumed);
17658 __tmp.put_f32_le(self.fuel_flow);
17659 __tmp.put_f32_le(self.engine_load);
17660 __tmp.put_f32_le(self.throttle_position);
17661 __tmp.put_f32_le(self.spark_dwell_time);
17662 __tmp.put_f32_le(self.barometric_pressure);
17663 __tmp.put_f32_le(self.intake_manifold_pressure);
17664 __tmp.put_f32_le(self.intake_manifold_temperature);
17665 __tmp.put_f32_le(self.cylinder_head_temperature);
17666 __tmp.put_f32_le(self.ignition_timing);
17667 __tmp.put_f32_le(self.injection_time);
17668 __tmp.put_f32_le(self.exhaust_gas_temperature);
17669 __tmp.put_f32_le(self.throttle_out);
17670 __tmp.put_f32_le(self.pt_compensation);
17671 __tmp.put_u8(self.health);
17672 __tmp.put_f32_le(self.ignition_voltage);
17673 __tmp.put_f32_le(self.fuel_pressure);
17674 if matches!(version, MavlinkVersion::V2) {
17675 let len = __tmp.len();
17676 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17677 } else {
17678 __tmp.len()
17679 }
17680 }
17681}
17682#[doc = "id: 122"]
17683#[doc = "Stop log transfer and resume normal logging."]
17684#[derive(Debug, Clone, PartialEq)]
17685#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17686#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17687pub struct LOG_REQUEST_END_DATA {
17688 #[doc = "System ID"]
17689 pub target_system: u8,
17690 #[doc = "Component ID"]
17691 pub target_component: u8,
17692}
17693impl LOG_REQUEST_END_DATA {
17694 pub const ENCODED_LEN: usize = 2usize;
17695 pub const DEFAULT: Self = Self {
17696 target_system: 0_u8,
17697 target_component: 0_u8,
17698 };
17699 #[cfg(feature = "arbitrary")]
17700 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17701 use arbitrary::{Arbitrary, Unstructured};
17702 let mut buf = [0u8; 1024];
17703 rng.fill_bytes(&mut buf);
17704 let mut unstructured = Unstructured::new(&buf);
17705 Self::arbitrary(&mut unstructured).unwrap_or_default()
17706 }
17707}
17708impl Default for LOG_REQUEST_END_DATA {
17709 fn default() -> Self {
17710 Self::DEFAULT.clone()
17711 }
17712}
17713impl MessageData for LOG_REQUEST_END_DATA {
17714 type Message = MavMessage;
17715 const ID: u32 = 122u32;
17716 const NAME: &'static str = "LOG_REQUEST_END";
17717 const EXTRA_CRC: u8 = 203u8;
17718 const ENCODED_LEN: usize = 2usize;
17719 fn deser(
17720 _version: MavlinkVersion,
17721 __input: &[u8],
17722 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17723 let avail_len = __input.len();
17724 let mut payload_buf = [0; Self::ENCODED_LEN];
17725 let mut buf = if avail_len < Self::ENCODED_LEN {
17726 payload_buf[0..avail_len].copy_from_slice(__input);
17727 Bytes::new(&payload_buf)
17728 } else {
17729 Bytes::new(__input)
17730 };
17731 let mut __struct = Self::default();
17732 __struct.target_system = buf.get_u8();
17733 __struct.target_component = buf.get_u8();
17734 Ok(__struct)
17735 }
17736 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17737 let mut __tmp = BytesMut::new(bytes);
17738 #[allow(clippy::absurd_extreme_comparisons)]
17739 #[allow(unused_comparisons)]
17740 if __tmp.remaining() < Self::ENCODED_LEN {
17741 panic!(
17742 "buffer is too small (need {} bytes, but got {})",
17743 Self::ENCODED_LEN,
17744 __tmp.remaining(),
17745 )
17746 }
17747 __tmp.put_u8(self.target_system);
17748 __tmp.put_u8(self.target_component);
17749 if matches!(version, MavlinkVersion::V2) {
17750 let len = __tmp.len();
17751 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17752 } else {
17753 __tmp.len()
17754 }
17755 }
17756}
17757#[doc = "id: 287"]
17758#[doc = "Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation."]
17759#[derive(Debug, Clone, PartialEq)]
17760#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17761#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17762pub struct GIMBAL_MANAGER_SET_PITCHYAW_DATA {
17763 #[doc = "High level gimbal manager flags to use."]
17764 pub flags: GimbalManagerFlags,
17765 #[doc = "Pitch angle (positive: up, negative: down, NaN to be ignored)."]
17766 pub pitch: f32,
17767 #[doc = "Yaw angle (positive: to the right, negative: to the left, NaN to be ignored)."]
17768 pub yaw: f32,
17769 #[doc = "Pitch angular rate (positive: up, negative: down, NaN to be ignored)."]
17770 pub pitch_rate: f32,
17771 #[doc = "Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored)."]
17772 pub yaw_rate: f32,
17773 #[doc = "System ID"]
17774 pub target_system: u8,
17775 #[doc = "Component ID"]
17776 pub target_component: u8,
17777 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
17778 pub gimbal_device_id: u8,
17779}
17780impl GIMBAL_MANAGER_SET_PITCHYAW_DATA {
17781 pub const ENCODED_LEN: usize = 23usize;
17782 pub const DEFAULT: Self = Self {
17783 flags: GimbalManagerFlags::DEFAULT,
17784 pitch: 0.0_f32,
17785 yaw: 0.0_f32,
17786 pitch_rate: 0.0_f32,
17787 yaw_rate: 0.0_f32,
17788 target_system: 0_u8,
17789 target_component: 0_u8,
17790 gimbal_device_id: 0_u8,
17791 };
17792 #[cfg(feature = "arbitrary")]
17793 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17794 use arbitrary::{Arbitrary, Unstructured};
17795 let mut buf = [0u8; 1024];
17796 rng.fill_bytes(&mut buf);
17797 let mut unstructured = Unstructured::new(&buf);
17798 Self::arbitrary(&mut unstructured).unwrap_or_default()
17799 }
17800}
17801impl Default for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
17802 fn default() -> Self {
17803 Self::DEFAULT.clone()
17804 }
17805}
17806impl MessageData for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
17807 type Message = MavMessage;
17808 const ID: u32 = 287u32;
17809 const NAME: &'static str = "GIMBAL_MANAGER_SET_PITCHYAW";
17810 const EXTRA_CRC: u8 = 1u8;
17811 const ENCODED_LEN: usize = 23usize;
17812 fn deser(
17813 _version: MavlinkVersion,
17814 __input: &[u8],
17815 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17816 let avail_len = __input.len();
17817 let mut payload_buf = [0; Self::ENCODED_LEN];
17818 let mut buf = if avail_len < Self::ENCODED_LEN {
17819 payload_buf[0..avail_len].copy_from_slice(__input);
17820 Bytes::new(&payload_buf)
17821 } else {
17822 Bytes::new(__input)
17823 };
17824 let mut __struct = Self::default();
17825 let tmp = buf.get_u32_le();
17826 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
17827 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
17828 flag_type: "GimbalManagerFlags",
17829 value: tmp as u32,
17830 })?;
17831 __struct.pitch = buf.get_f32_le();
17832 __struct.yaw = buf.get_f32_le();
17833 __struct.pitch_rate = buf.get_f32_le();
17834 __struct.yaw_rate = buf.get_f32_le();
17835 __struct.target_system = buf.get_u8();
17836 __struct.target_component = buf.get_u8();
17837 __struct.gimbal_device_id = buf.get_u8();
17838 Ok(__struct)
17839 }
17840 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17841 let mut __tmp = BytesMut::new(bytes);
17842 #[allow(clippy::absurd_extreme_comparisons)]
17843 #[allow(unused_comparisons)]
17844 if __tmp.remaining() < Self::ENCODED_LEN {
17845 panic!(
17846 "buffer is too small (need {} bytes, but got {})",
17847 Self::ENCODED_LEN,
17848 __tmp.remaining(),
17849 )
17850 }
17851 __tmp.put_u32_le(self.flags.bits());
17852 __tmp.put_f32_le(self.pitch);
17853 __tmp.put_f32_le(self.yaw);
17854 __tmp.put_f32_le(self.pitch_rate);
17855 __tmp.put_f32_le(self.yaw_rate);
17856 __tmp.put_u8(self.target_system);
17857 __tmp.put_u8(self.target_component);
17858 __tmp.put_u8(self.gimbal_device_id);
17859 if matches!(version, MavlinkVersion::V2) {
17860 let len = __tmp.len();
17861 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17862 } else {
17863 __tmp.len()
17864 }
17865 }
17866}
17867#[doc = "id: 311"]
17868#[doc = "General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service \"uavcan.protocol.GetNodeInfo\" for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at <http://uavcan.org>."]
17869#[derive(Debug, Clone, PartialEq)]
17870#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17871#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17872pub struct UAVCAN_NODE_INFO_DATA {
17873 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17874 pub time_usec: u64,
17875 #[doc = "Time since the start-up of the node."]
17876 pub uptime_sec: u32,
17877 #[doc = "Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown."]
17878 pub sw_vcs_commit: u32,
17879 #[doc = "Node name string. For example, \"sapog.px4.io\"."]
17880 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17881 pub name: [u8; 80],
17882 #[doc = "Hardware major version number."]
17883 pub hw_version_major: u8,
17884 #[doc = "Hardware minor version number."]
17885 pub hw_version_minor: u8,
17886 #[doc = "Hardware unique 128-bit ID."]
17887 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17888 pub hw_unique_id: [u8; 16],
17889 #[doc = "Software major version number."]
17890 pub sw_version_major: u8,
17891 #[doc = "Software minor version number."]
17892 pub sw_version_minor: u8,
17893}
17894impl UAVCAN_NODE_INFO_DATA {
17895 pub const ENCODED_LEN: usize = 116usize;
17896 pub const DEFAULT: Self = Self {
17897 time_usec: 0_u64,
17898 uptime_sec: 0_u32,
17899 sw_vcs_commit: 0_u32,
17900 name: [0_u8; 80usize],
17901 hw_version_major: 0_u8,
17902 hw_version_minor: 0_u8,
17903 hw_unique_id: [0_u8; 16usize],
17904 sw_version_major: 0_u8,
17905 sw_version_minor: 0_u8,
17906 };
17907 #[cfg(feature = "arbitrary")]
17908 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17909 use arbitrary::{Arbitrary, Unstructured};
17910 let mut buf = [0u8; 1024];
17911 rng.fill_bytes(&mut buf);
17912 let mut unstructured = Unstructured::new(&buf);
17913 Self::arbitrary(&mut unstructured).unwrap_or_default()
17914 }
17915}
17916impl Default for UAVCAN_NODE_INFO_DATA {
17917 fn default() -> Self {
17918 Self::DEFAULT.clone()
17919 }
17920}
17921impl MessageData for UAVCAN_NODE_INFO_DATA {
17922 type Message = MavMessage;
17923 const ID: u32 = 311u32;
17924 const NAME: &'static str = "UAVCAN_NODE_INFO";
17925 const EXTRA_CRC: u8 = 95u8;
17926 const ENCODED_LEN: usize = 116usize;
17927 fn deser(
17928 _version: MavlinkVersion,
17929 __input: &[u8],
17930 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17931 let avail_len = __input.len();
17932 let mut payload_buf = [0; Self::ENCODED_LEN];
17933 let mut buf = if avail_len < Self::ENCODED_LEN {
17934 payload_buf[0..avail_len].copy_from_slice(__input);
17935 Bytes::new(&payload_buf)
17936 } else {
17937 Bytes::new(__input)
17938 };
17939 let mut __struct = Self::default();
17940 __struct.time_usec = buf.get_u64_le();
17941 __struct.uptime_sec = buf.get_u32_le();
17942 __struct.sw_vcs_commit = buf.get_u32_le();
17943 for v in &mut __struct.name {
17944 let val = buf.get_u8();
17945 *v = val;
17946 }
17947 __struct.hw_version_major = buf.get_u8();
17948 __struct.hw_version_minor = buf.get_u8();
17949 for v in &mut __struct.hw_unique_id {
17950 let val = buf.get_u8();
17951 *v = val;
17952 }
17953 __struct.sw_version_major = buf.get_u8();
17954 __struct.sw_version_minor = buf.get_u8();
17955 Ok(__struct)
17956 }
17957 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17958 let mut __tmp = BytesMut::new(bytes);
17959 #[allow(clippy::absurd_extreme_comparisons)]
17960 #[allow(unused_comparisons)]
17961 if __tmp.remaining() < Self::ENCODED_LEN {
17962 panic!(
17963 "buffer is too small (need {} bytes, but got {})",
17964 Self::ENCODED_LEN,
17965 __tmp.remaining(),
17966 )
17967 }
17968 __tmp.put_u64_le(self.time_usec);
17969 __tmp.put_u32_le(self.uptime_sec);
17970 __tmp.put_u32_le(self.sw_vcs_commit);
17971 for val in &self.name {
17972 __tmp.put_u8(*val);
17973 }
17974 __tmp.put_u8(self.hw_version_major);
17975 __tmp.put_u8(self.hw_version_minor);
17976 for val in &self.hw_unique_id {
17977 __tmp.put_u8(*val);
17978 }
17979 __tmp.put_u8(self.sw_version_major);
17980 __tmp.put_u8(self.sw_version_minor);
17981 if matches!(version, MavlinkVersion::V2) {
17982 let len = __tmp.len();
17983 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17984 } else {
17985 __tmp.len()
17986 }
17987 }
17988}
17989#[doc = "id: 127"]
17990#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
17991#[derive(Debug, Clone, PartialEq)]
17992#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17993#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17994pub struct GPS_RTK_DATA {
17995 #[doc = "Time since boot of last baseline message received."]
17996 pub time_last_baseline_ms: u32,
17997 #[doc = "GPS Time of Week of last baseline"]
17998 pub tow: u32,
17999 #[doc = "Current baseline in ECEF x or NED north component."]
18000 pub baseline_a_mm: i32,
18001 #[doc = "Current baseline in ECEF y or NED east component."]
18002 pub baseline_b_mm: i32,
18003 #[doc = "Current baseline in ECEF z or NED down component."]
18004 pub baseline_c_mm: i32,
18005 #[doc = "Current estimate of baseline accuracy."]
18006 pub accuracy: u32,
18007 #[doc = "Current number of integer ambiguity hypotheses."]
18008 pub iar_num_hypotheses: i32,
18009 #[doc = "GPS Week Number of last baseline"]
18010 pub wn: u16,
18011 #[doc = "Identification of connected RTK receiver."]
18012 pub rtk_receiver_id: u8,
18013 #[doc = "GPS-specific health report for RTK data."]
18014 pub rtk_health: u8,
18015 #[doc = "Rate of baseline messages being received by GPS"]
18016 pub rtk_rate: u8,
18017 #[doc = "Current number of sats used for RTK calculation."]
18018 pub nsats: u8,
18019 #[doc = "Coordinate system of baseline"]
18020 pub baseline_coords_type: RtkBaselineCoordinateSystem,
18021}
18022impl GPS_RTK_DATA {
18023 pub const ENCODED_LEN: usize = 35usize;
18024 pub const DEFAULT: Self = Self {
18025 time_last_baseline_ms: 0_u32,
18026 tow: 0_u32,
18027 baseline_a_mm: 0_i32,
18028 baseline_b_mm: 0_i32,
18029 baseline_c_mm: 0_i32,
18030 accuracy: 0_u32,
18031 iar_num_hypotheses: 0_i32,
18032 wn: 0_u16,
18033 rtk_receiver_id: 0_u8,
18034 rtk_health: 0_u8,
18035 rtk_rate: 0_u8,
18036 nsats: 0_u8,
18037 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
18038 };
18039 #[cfg(feature = "arbitrary")]
18040 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18041 use arbitrary::{Arbitrary, Unstructured};
18042 let mut buf = [0u8; 1024];
18043 rng.fill_bytes(&mut buf);
18044 let mut unstructured = Unstructured::new(&buf);
18045 Self::arbitrary(&mut unstructured).unwrap_or_default()
18046 }
18047}
18048impl Default for GPS_RTK_DATA {
18049 fn default() -> Self {
18050 Self::DEFAULT.clone()
18051 }
18052}
18053impl MessageData for GPS_RTK_DATA {
18054 type Message = MavMessage;
18055 const ID: u32 = 127u32;
18056 const NAME: &'static str = "GPS_RTK";
18057 const EXTRA_CRC: u8 = 25u8;
18058 const ENCODED_LEN: usize = 35usize;
18059 fn deser(
18060 _version: MavlinkVersion,
18061 __input: &[u8],
18062 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18063 let avail_len = __input.len();
18064 let mut payload_buf = [0; Self::ENCODED_LEN];
18065 let mut buf = if avail_len < Self::ENCODED_LEN {
18066 payload_buf[0..avail_len].copy_from_slice(__input);
18067 Bytes::new(&payload_buf)
18068 } else {
18069 Bytes::new(__input)
18070 };
18071 let mut __struct = Self::default();
18072 __struct.time_last_baseline_ms = buf.get_u32_le();
18073 __struct.tow = buf.get_u32_le();
18074 __struct.baseline_a_mm = buf.get_i32_le();
18075 __struct.baseline_b_mm = buf.get_i32_le();
18076 __struct.baseline_c_mm = buf.get_i32_le();
18077 __struct.accuracy = buf.get_u32_le();
18078 __struct.iar_num_hypotheses = buf.get_i32_le();
18079 __struct.wn = buf.get_u16_le();
18080 __struct.rtk_receiver_id = buf.get_u8();
18081 __struct.rtk_health = buf.get_u8();
18082 __struct.rtk_rate = buf.get_u8();
18083 __struct.nsats = buf.get_u8();
18084 let tmp = buf.get_u8();
18085 __struct.baseline_coords_type =
18086 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18087 enum_type: "RtkBaselineCoordinateSystem",
18088 value: tmp as u32,
18089 })?;
18090 Ok(__struct)
18091 }
18092 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18093 let mut __tmp = BytesMut::new(bytes);
18094 #[allow(clippy::absurd_extreme_comparisons)]
18095 #[allow(unused_comparisons)]
18096 if __tmp.remaining() < Self::ENCODED_LEN {
18097 panic!(
18098 "buffer is too small (need {} bytes, but got {})",
18099 Self::ENCODED_LEN,
18100 __tmp.remaining(),
18101 )
18102 }
18103 __tmp.put_u32_le(self.time_last_baseline_ms);
18104 __tmp.put_u32_le(self.tow);
18105 __tmp.put_i32_le(self.baseline_a_mm);
18106 __tmp.put_i32_le(self.baseline_b_mm);
18107 __tmp.put_i32_le(self.baseline_c_mm);
18108 __tmp.put_u32_le(self.accuracy);
18109 __tmp.put_i32_le(self.iar_num_hypotheses);
18110 __tmp.put_u16_le(self.wn);
18111 __tmp.put_u8(self.rtk_receiver_id);
18112 __tmp.put_u8(self.rtk_health);
18113 __tmp.put_u8(self.rtk_rate);
18114 __tmp.put_u8(self.nsats);
18115 __tmp.put_u8(self.baseline_coords_type as u8);
18116 if matches!(version, MavlinkVersion::V2) {
18117 let len = __tmp.len();
18118 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18119 } else {
18120 __tmp.len()
18121 }
18122 }
18123}
18124#[doc = "id: 51"]
18125#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. <https://mavlink.io/en/services/mission.html>."]
18126#[derive(Debug, Clone, PartialEq)]
18127#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18128#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18129pub struct MISSION_REQUEST_INT_DATA {
18130 #[doc = "Sequence"]
18131 pub seq: u16,
18132 #[doc = "System ID"]
18133 pub target_system: u8,
18134 #[doc = "Component ID"]
18135 pub target_component: u8,
18136 #[doc = "Mission type."]
18137 #[cfg_attr(feature = "serde", serde(default))]
18138 pub mission_type: MavMissionType,
18139}
18140impl MISSION_REQUEST_INT_DATA {
18141 pub const ENCODED_LEN: usize = 5usize;
18142 pub const DEFAULT: Self = Self {
18143 seq: 0_u16,
18144 target_system: 0_u8,
18145 target_component: 0_u8,
18146 mission_type: MavMissionType::DEFAULT,
18147 };
18148 #[cfg(feature = "arbitrary")]
18149 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18150 use arbitrary::{Arbitrary, Unstructured};
18151 let mut buf = [0u8; 1024];
18152 rng.fill_bytes(&mut buf);
18153 let mut unstructured = Unstructured::new(&buf);
18154 Self::arbitrary(&mut unstructured).unwrap_or_default()
18155 }
18156}
18157impl Default for MISSION_REQUEST_INT_DATA {
18158 fn default() -> Self {
18159 Self::DEFAULT.clone()
18160 }
18161}
18162impl MessageData for MISSION_REQUEST_INT_DATA {
18163 type Message = MavMessage;
18164 const ID: u32 = 51u32;
18165 const NAME: &'static str = "MISSION_REQUEST_INT";
18166 const EXTRA_CRC: u8 = 196u8;
18167 const ENCODED_LEN: usize = 5usize;
18168 fn deser(
18169 _version: MavlinkVersion,
18170 __input: &[u8],
18171 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18172 let avail_len = __input.len();
18173 let mut payload_buf = [0; Self::ENCODED_LEN];
18174 let mut buf = if avail_len < Self::ENCODED_LEN {
18175 payload_buf[0..avail_len].copy_from_slice(__input);
18176 Bytes::new(&payload_buf)
18177 } else {
18178 Bytes::new(__input)
18179 };
18180 let mut __struct = Self::default();
18181 __struct.seq = buf.get_u16_le();
18182 __struct.target_system = buf.get_u8();
18183 __struct.target_component = buf.get_u8();
18184 let tmp = buf.get_u8();
18185 __struct.mission_type =
18186 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18187 enum_type: "MavMissionType",
18188 value: tmp as u32,
18189 })?;
18190 Ok(__struct)
18191 }
18192 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18193 let mut __tmp = BytesMut::new(bytes);
18194 #[allow(clippy::absurd_extreme_comparisons)]
18195 #[allow(unused_comparisons)]
18196 if __tmp.remaining() < Self::ENCODED_LEN {
18197 panic!(
18198 "buffer is too small (need {} bytes, but got {})",
18199 Self::ENCODED_LEN,
18200 __tmp.remaining(),
18201 )
18202 }
18203 __tmp.put_u16_le(self.seq);
18204 __tmp.put_u8(self.target_system);
18205 __tmp.put_u8(self.target_component);
18206 __tmp.put_u8(self.mission_type as u8);
18207 if matches!(version, MavlinkVersion::V2) {
18208 let len = __tmp.len();
18209 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18210 } else {
18211 __tmp.len()
18212 }
18213 }
18214}
18215#[doc = "id: 4"]
18216#[doc = "A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at <https://mavlink.io/en/services/ping.html>."]
18217#[derive(Debug, Clone, PartialEq)]
18218#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18219#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18220pub struct PING_DATA {
18221 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18222 pub time_usec: u64,
18223 #[doc = "PING sequence"]
18224 pub seq: u32,
18225 #[doc = "0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system"]
18226 pub target_system: u8,
18227 #[doc = "0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component."]
18228 pub target_component: u8,
18229}
18230impl PING_DATA {
18231 pub const ENCODED_LEN: usize = 14usize;
18232 pub const DEFAULT: Self = Self {
18233 time_usec: 0_u64,
18234 seq: 0_u32,
18235 target_system: 0_u8,
18236 target_component: 0_u8,
18237 };
18238 #[cfg(feature = "arbitrary")]
18239 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18240 use arbitrary::{Arbitrary, Unstructured};
18241 let mut buf = [0u8; 1024];
18242 rng.fill_bytes(&mut buf);
18243 let mut unstructured = Unstructured::new(&buf);
18244 Self::arbitrary(&mut unstructured).unwrap_or_default()
18245 }
18246}
18247impl Default for PING_DATA {
18248 fn default() -> Self {
18249 Self::DEFAULT.clone()
18250 }
18251}
18252impl MessageData for PING_DATA {
18253 type Message = MavMessage;
18254 const ID: u32 = 4u32;
18255 const NAME: &'static str = "PING";
18256 const EXTRA_CRC: u8 = 237u8;
18257 const ENCODED_LEN: usize = 14usize;
18258 fn deser(
18259 _version: MavlinkVersion,
18260 __input: &[u8],
18261 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18262 let avail_len = __input.len();
18263 let mut payload_buf = [0; Self::ENCODED_LEN];
18264 let mut buf = if avail_len < Self::ENCODED_LEN {
18265 payload_buf[0..avail_len].copy_from_slice(__input);
18266 Bytes::new(&payload_buf)
18267 } else {
18268 Bytes::new(__input)
18269 };
18270 let mut __struct = Self::default();
18271 __struct.time_usec = buf.get_u64_le();
18272 __struct.seq = buf.get_u32_le();
18273 __struct.target_system = buf.get_u8();
18274 __struct.target_component = buf.get_u8();
18275 Ok(__struct)
18276 }
18277 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18278 let mut __tmp = BytesMut::new(bytes);
18279 #[allow(clippy::absurd_extreme_comparisons)]
18280 #[allow(unused_comparisons)]
18281 if __tmp.remaining() < Self::ENCODED_LEN {
18282 panic!(
18283 "buffer is too small (need {} bytes, but got {})",
18284 Self::ENCODED_LEN,
18285 __tmp.remaining(),
18286 )
18287 }
18288 __tmp.put_u64_le(self.time_usec);
18289 __tmp.put_u32_le(self.seq);
18290 __tmp.put_u8(self.target_system);
18291 __tmp.put_u8(self.target_component);
18292 if matches!(version, MavlinkVersion::V2) {
18293 let len = __tmp.len();
18294 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18295 } else {
18296 __tmp.len()
18297 }
18298 }
18299}
18300#[doc = "id: 350"]
18301#[doc = "Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code."]
18302#[derive(Debug, Clone, PartialEq)]
18303#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18304#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18305pub struct DEBUG_FLOAT_ARRAY_DATA {
18306 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18307 pub time_usec: u64,
18308 #[doc = "Unique ID used to discriminate between arrays"]
18309 pub array_id: u16,
18310 #[doc = "Name, for human-friendly display in a Ground Control Station"]
18311 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18312 pub name: [u8; 10],
18313 #[doc = "data"]
18314 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18315 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18316 pub data: [f32; 58],
18317}
18318impl DEBUG_FLOAT_ARRAY_DATA {
18319 pub const ENCODED_LEN: usize = 252usize;
18320 pub const DEFAULT: Self = Self {
18321 time_usec: 0_u64,
18322 array_id: 0_u16,
18323 name: [0_u8; 10usize],
18324 data: [0.0_f32; 58usize],
18325 };
18326 #[cfg(feature = "arbitrary")]
18327 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18328 use arbitrary::{Arbitrary, Unstructured};
18329 let mut buf = [0u8; 1024];
18330 rng.fill_bytes(&mut buf);
18331 let mut unstructured = Unstructured::new(&buf);
18332 Self::arbitrary(&mut unstructured).unwrap_or_default()
18333 }
18334}
18335impl Default for DEBUG_FLOAT_ARRAY_DATA {
18336 fn default() -> Self {
18337 Self::DEFAULT.clone()
18338 }
18339}
18340impl MessageData for DEBUG_FLOAT_ARRAY_DATA {
18341 type Message = MavMessage;
18342 const ID: u32 = 350u32;
18343 const NAME: &'static str = "DEBUG_FLOAT_ARRAY";
18344 const EXTRA_CRC: u8 = 232u8;
18345 const ENCODED_LEN: usize = 252usize;
18346 fn deser(
18347 _version: MavlinkVersion,
18348 __input: &[u8],
18349 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18350 let avail_len = __input.len();
18351 let mut payload_buf = [0; Self::ENCODED_LEN];
18352 let mut buf = if avail_len < Self::ENCODED_LEN {
18353 payload_buf[0..avail_len].copy_from_slice(__input);
18354 Bytes::new(&payload_buf)
18355 } else {
18356 Bytes::new(__input)
18357 };
18358 let mut __struct = Self::default();
18359 __struct.time_usec = buf.get_u64_le();
18360 __struct.array_id = buf.get_u16_le();
18361 for v in &mut __struct.name {
18362 let val = buf.get_u8();
18363 *v = val;
18364 }
18365 for v in &mut __struct.data {
18366 let val = buf.get_f32_le();
18367 *v = val;
18368 }
18369 Ok(__struct)
18370 }
18371 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18372 let mut __tmp = BytesMut::new(bytes);
18373 #[allow(clippy::absurd_extreme_comparisons)]
18374 #[allow(unused_comparisons)]
18375 if __tmp.remaining() < Self::ENCODED_LEN {
18376 panic!(
18377 "buffer is too small (need {} bytes, but got {})",
18378 Self::ENCODED_LEN,
18379 __tmp.remaining(),
18380 )
18381 }
18382 __tmp.put_u64_le(self.time_usec);
18383 __tmp.put_u16_le(self.array_id);
18384 for val in &self.name {
18385 __tmp.put_u8(*val);
18386 }
18387 for val in &self.data {
18388 __tmp.put_f32_le(*val);
18389 }
18390 if matches!(version, MavlinkVersion::V2) {
18391 let len = __tmp.len();
18392 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18393 } else {
18394 __tmp.len()
18395 }
18396 }
18397}
18398#[doc = "id: 256"]
18399#[doc = "Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing."]
18400#[derive(Debug, Clone, PartialEq)]
18401#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18402#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18403pub struct SETUP_SIGNING_DATA {
18404 #[doc = "initial timestamp"]
18405 pub initial_timestamp: u64,
18406 #[doc = "system id of the target"]
18407 pub target_system: u8,
18408 #[doc = "component ID of the target"]
18409 pub target_component: u8,
18410 #[doc = "signing key"]
18411 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18412 pub secret_key: [u8; 32],
18413}
18414impl SETUP_SIGNING_DATA {
18415 pub const ENCODED_LEN: usize = 42usize;
18416 pub const DEFAULT: Self = Self {
18417 initial_timestamp: 0_u64,
18418 target_system: 0_u8,
18419 target_component: 0_u8,
18420 secret_key: [0_u8; 32usize],
18421 };
18422 #[cfg(feature = "arbitrary")]
18423 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18424 use arbitrary::{Arbitrary, Unstructured};
18425 let mut buf = [0u8; 1024];
18426 rng.fill_bytes(&mut buf);
18427 let mut unstructured = Unstructured::new(&buf);
18428 Self::arbitrary(&mut unstructured).unwrap_or_default()
18429 }
18430}
18431impl Default for SETUP_SIGNING_DATA {
18432 fn default() -> Self {
18433 Self::DEFAULT.clone()
18434 }
18435}
18436impl MessageData for SETUP_SIGNING_DATA {
18437 type Message = MavMessage;
18438 const ID: u32 = 256u32;
18439 const NAME: &'static str = "SETUP_SIGNING";
18440 const EXTRA_CRC: u8 = 71u8;
18441 const ENCODED_LEN: usize = 42usize;
18442 fn deser(
18443 _version: MavlinkVersion,
18444 __input: &[u8],
18445 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18446 let avail_len = __input.len();
18447 let mut payload_buf = [0; Self::ENCODED_LEN];
18448 let mut buf = if avail_len < Self::ENCODED_LEN {
18449 payload_buf[0..avail_len].copy_from_slice(__input);
18450 Bytes::new(&payload_buf)
18451 } else {
18452 Bytes::new(__input)
18453 };
18454 let mut __struct = Self::default();
18455 __struct.initial_timestamp = buf.get_u64_le();
18456 __struct.target_system = buf.get_u8();
18457 __struct.target_component = buf.get_u8();
18458 for v in &mut __struct.secret_key {
18459 let val = buf.get_u8();
18460 *v = val;
18461 }
18462 Ok(__struct)
18463 }
18464 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18465 let mut __tmp = BytesMut::new(bytes);
18466 #[allow(clippy::absurd_extreme_comparisons)]
18467 #[allow(unused_comparisons)]
18468 if __tmp.remaining() < Self::ENCODED_LEN {
18469 panic!(
18470 "buffer is too small (need {} bytes, but got {})",
18471 Self::ENCODED_LEN,
18472 __tmp.remaining(),
18473 )
18474 }
18475 __tmp.put_u64_le(self.initial_timestamp);
18476 __tmp.put_u8(self.target_system);
18477 __tmp.put_u8(self.target_component);
18478 for val in &self.secret_key {
18479 __tmp.put_u8(*val);
18480 }
18481 if matches!(version, MavlinkVersion::V2) {
18482 let len = __tmp.len();
18483 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18484 } else {
18485 __tmp.len()
18486 }
18487 }
18488}
18489#[doc = "id: 263"]
18490#[doc = "Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range."]
18491#[derive(Debug, Clone, PartialEq)]
18492#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18493#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18494pub struct CAMERA_IMAGE_CAPTURED_DATA {
18495 #[doc = "Timestamp (time since UNIX epoch) in UTC. 0 for unknown."]
18496 pub time_utc: u64,
18497 #[doc = "Timestamp (time since system boot)."]
18498 pub time_boot_ms: u32,
18499 #[doc = "Latitude where image was taken"]
18500 pub lat: i32,
18501 #[doc = "Longitude where capture was taken"]
18502 pub lon: i32,
18503 #[doc = "Altitude (MSL) where image was taken"]
18504 pub alt: i32,
18505 #[doc = "Altitude above ground"]
18506 pub relative_alt: i32,
18507 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
18508 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18509 pub q: [f32; 4],
18510 #[doc = "Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)"]
18511 pub image_index: i32,
18512 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). Field name is usually camera_device_id."]
18513 pub camera_id: u8,
18514 #[doc = "Boolean indicating success (1) or failure (0) while capturing this image."]
18515 pub capture_result: i8,
18516 #[doc = "URL of image taken. Either local storage or <http://foo.jpg> if camera provides an HTTP interface."]
18517 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18518 pub file_url: [u8; 205],
18519}
18520impl CAMERA_IMAGE_CAPTURED_DATA {
18521 pub const ENCODED_LEN: usize = 255usize;
18522 pub const DEFAULT: Self = Self {
18523 time_utc: 0_u64,
18524 time_boot_ms: 0_u32,
18525 lat: 0_i32,
18526 lon: 0_i32,
18527 alt: 0_i32,
18528 relative_alt: 0_i32,
18529 q: [0.0_f32; 4usize],
18530 image_index: 0_i32,
18531 camera_id: 0_u8,
18532 capture_result: 0_i8,
18533 file_url: [0_u8; 205usize],
18534 };
18535 #[cfg(feature = "arbitrary")]
18536 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18537 use arbitrary::{Arbitrary, Unstructured};
18538 let mut buf = [0u8; 1024];
18539 rng.fill_bytes(&mut buf);
18540 let mut unstructured = Unstructured::new(&buf);
18541 Self::arbitrary(&mut unstructured).unwrap_or_default()
18542 }
18543}
18544impl Default for CAMERA_IMAGE_CAPTURED_DATA {
18545 fn default() -> Self {
18546 Self::DEFAULT.clone()
18547 }
18548}
18549impl MessageData for CAMERA_IMAGE_CAPTURED_DATA {
18550 type Message = MavMessage;
18551 const ID: u32 = 263u32;
18552 const NAME: &'static str = "CAMERA_IMAGE_CAPTURED";
18553 const EXTRA_CRC: u8 = 133u8;
18554 const ENCODED_LEN: usize = 255usize;
18555 fn deser(
18556 _version: MavlinkVersion,
18557 __input: &[u8],
18558 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18559 let avail_len = __input.len();
18560 let mut payload_buf = [0; Self::ENCODED_LEN];
18561 let mut buf = if avail_len < Self::ENCODED_LEN {
18562 payload_buf[0..avail_len].copy_from_slice(__input);
18563 Bytes::new(&payload_buf)
18564 } else {
18565 Bytes::new(__input)
18566 };
18567 let mut __struct = Self::default();
18568 __struct.time_utc = buf.get_u64_le();
18569 __struct.time_boot_ms = buf.get_u32_le();
18570 __struct.lat = buf.get_i32_le();
18571 __struct.lon = buf.get_i32_le();
18572 __struct.alt = buf.get_i32_le();
18573 __struct.relative_alt = buf.get_i32_le();
18574 for v in &mut __struct.q {
18575 let val = buf.get_f32_le();
18576 *v = val;
18577 }
18578 __struct.image_index = buf.get_i32_le();
18579 __struct.camera_id = buf.get_u8();
18580 __struct.capture_result = buf.get_i8();
18581 for v in &mut __struct.file_url {
18582 let val = buf.get_u8();
18583 *v = val;
18584 }
18585 Ok(__struct)
18586 }
18587 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18588 let mut __tmp = BytesMut::new(bytes);
18589 #[allow(clippy::absurd_extreme_comparisons)]
18590 #[allow(unused_comparisons)]
18591 if __tmp.remaining() < Self::ENCODED_LEN {
18592 panic!(
18593 "buffer is too small (need {} bytes, but got {})",
18594 Self::ENCODED_LEN,
18595 __tmp.remaining(),
18596 )
18597 }
18598 __tmp.put_u64_le(self.time_utc);
18599 __tmp.put_u32_le(self.time_boot_ms);
18600 __tmp.put_i32_le(self.lat);
18601 __tmp.put_i32_le(self.lon);
18602 __tmp.put_i32_le(self.alt);
18603 __tmp.put_i32_le(self.relative_alt);
18604 for val in &self.q {
18605 __tmp.put_f32_le(*val);
18606 }
18607 __tmp.put_i32_le(self.image_index);
18608 __tmp.put_u8(self.camera_id);
18609 __tmp.put_i8(self.capture_result);
18610 for val in &self.file_url {
18611 __tmp.put_u8(*val);
18612 }
18613 if matches!(version, MavlinkVersion::V2) {
18614 let len = __tmp.len();
18615 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18616 } else {
18617 __tmp.len()
18618 }
18619 }
18620}
18621#[doc = "id: 147"]
18622#[doc = "Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send BATTERY_INFO."]
18623#[derive(Debug, Clone, PartialEq)]
18624#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18625#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18626pub struct BATTERY_STATUS_DATA {
18627 #[doc = "Consumed charge, -1: autopilot does not provide consumption estimate"]
18628 pub current_consumed: i32,
18629 #[doc = "Consumed energy, -1: autopilot does not provide energy consumption estimate"]
18630 pub energy_consumed: i32,
18631 #[doc = "Temperature of the battery. INT16_MAX for unknown temperature."]
18632 pub temperature: i16,
18633 #[doc = "Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1)."]
18634 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18635 pub voltages: [u16; 10],
18636 #[doc = "Battery current, -1: autopilot does not measure the current"]
18637 pub current_battery: i16,
18638 #[doc = "Battery ID"]
18639 pub id: u8,
18640 #[doc = "Function of the battery"]
18641 pub battery_function: MavBatteryFunction,
18642 #[doc = "Type (chemistry) of the battery"]
18643 pub mavtype: MavBatteryType,
18644 #[doc = "Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery."]
18645 pub battery_remaining: i8,
18646 #[doc = "Remaining battery time, 0: autopilot does not provide remaining battery time estimate"]
18647 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18648 pub time_remaining: i32,
18649 #[doc = "State for extent of discharge, provided by autopilot for warning or external reactions"]
18650 #[cfg_attr(feature = "serde", serde(default))]
18651 pub charge_state: MavBatteryChargeState,
18652 #[doc = "Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead."]
18653 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18654 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18655 pub voltages_ext: [u16; 4],
18656 #[doc = "Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode."]
18657 #[cfg_attr(feature = "serde", serde(default))]
18658 pub mode: MavBatteryMode,
18659 #[doc = "Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported)."]
18660 #[cfg_attr(feature = "serde", serde(default))]
18661 pub fault_bitmask: MavBatteryFault,
18662}
18663impl BATTERY_STATUS_DATA {
18664 pub const ENCODED_LEN: usize = 54usize;
18665 pub const DEFAULT: Self = Self {
18666 current_consumed: 0_i32,
18667 energy_consumed: 0_i32,
18668 temperature: 0_i16,
18669 voltages: [0_u16; 10usize],
18670 current_battery: 0_i16,
18671 id: 0_u8,
18672 battery_function: MavBatteryFunction::DEFAULT,
18673 mavtype: MavBatteryType::DEFAULT,
18674 battery_remaining: 0_i8,
18675 time_remaining: 0_i32,
18676 charge_state: MavBatteryChargeState::DEFAULT,
18677 voltages_ext: [0_u16; 4usize],
18678 mode: MavBatteryMode::DEFAULT,
18679 fault_bitmask: MavBatteryFault::DEFAULT,
18680 };
18681 #[cfg(feature = "arbitrary")]
18682 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18683 use arbitrary::{Arbitrary, Unstructured};
18684 let mut buf = [0u8; 1024];
18685 rng.fill_bytes(&mut buf);
18686 let mut unstructured = Unstructured::new(&buf);
18687 Self::arbitrary(&mut unstructured).unwrap_or_default()
18688 }
18689}
18690impl Default for BATTERY_STATUS_DATA {
18691 fn default() -> Self {
18692 Self::DEFAULT.clone()
18693 }
18694}
18695impl MessageData for BATTERY_STATUS_DATA {
18696 type Message = MavMessage;
18697 const ID: u32 = 147u32;
18698 const NAME: &'static str = "BATTERY_STATUS";
18699 const EXTRA_CRC: u8 = 154u8;
18700 const ENCODED_LEN: usize = 54usize;
18701 fn deser(
18702 _version: MavlinkVersion,
18703 __input: &[u8],
18704 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18705 let avail_len = __input.len();
18706 let mut payload_buf = [0; Self::ENCODED_LEN];
18707 let mut buf = if avail_len < Self::ENCODED_LEN {
18708 payload_buf[0..avail_len].copy_from_slice(__input);
18709 Bytes::new(&payload_buf)
18710 } else {
18711 Bytes::new(__input)
18712 };
18713 let mut __struct = Self::default();
18714 __struct.current_consumed = buf.get_i32_le();
18715 __struct.energy_consumed = buf.get_i32_le();
18716 __struct.temperature = buf.get_i16_le();
18717 for v in &mut __struct.voltages {
18718 let val = buf.get_u16_le();
18719 *v = val;
18720 }
18721 __struct.current_battery = buf.get_i16_le();
18722 __struct.id = buf.get_u8();
18723 let tmp = buf.get_u8();
18724 __struct.battery_function =
18725 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18726 enum_type: "MavBatteryFunction",
18727 value: tmp as u32,
18728 })?;
18729 let tmp = buf.get_u8();
18730 __struct.mavtype =
18731 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18732 enum_type: "MavBatteryType",
18733 value: tmp as u32,
18734 })?;
18735 __struct.battery_remaining = buf.get_i8();
18736 __struct.time_remaining = buf.get_i32_le();
18737 let tmp = buf.get_u8();
18738 __struct.charge_state =
18739 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18740 enum_type: "MavBatteryChargeState",
18741 value: tmp as u32,
18742 })?;
18743 for v in &mut __struct.voltages_ext {
18744 let val = buf.get_u16_le();
18745 *v = val;
18746 }
18747 let tmp = buf.get_u8();
18748 __struct.mode =
18749 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18750 enum_type: "MavBatteryMode",
18751 value: tmp as u32,
18752 })?;
18753 let tmp = buf.get_u32_le();
18754 __struct.fault_bitmask = MavBatteryFault::from_bits(tmp & MavBatteryFault::all().bits())
18755 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
18756 flag_type: "MavBatteryFault",
18757 value: tmp as u32,
18758 })?;
18759 Ok(__struct)
18760 }
18761 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18762 let mut __tmp = BytesMut::new(bytes);
18763 #[allow(clippy::absurd_extreme_comparisons)]
18764 #[allow(unused_comparisons)]
18765 if __tmp.remaining() < Self::ENCODED_LEN {
18766 panic!(
18767 "buffer is too small (need {} bytes, but got {})",
18768 Self::ENCODED_LEN,
18769 __tmp.remaining(),
18770 )
18771 }
18772 __tmp.put_i32_le(self.current_consumed);
18773 __tmp.put_i32_le(self.energy_consumed);
18774 __tmp.put_i16_le(self.temperature);
18775 for val in &self.voltages {
18776 __tmp.put_u16_le(*val);
18777 }
18778 __tmp.put_i16_le(self.current_battery);
18779 __tmp.put_u8(self.id);
18780 __tmp.put_u8(self.battery_function as u8);
18781 __tmp.put_u8(self.mavtype as u8);
18782 __tmp.put_i8(self.battery_remaining);
18783 __tmp.put_i32_le(self.time_remaining);
18784 __tmp.put_u8(self.charge_state as u8);
18785 for val in &self.voltages_ext {
18786 __tmp.put_u16_le(*val);
18787 }
18788 __tmp.put_u8(self.mode as u8);
18789 __tmp.put_u32_le(self.fault_bitmask.bits());
18790 if matches!(version, MavlinkVersion::V2) {
18791 let len = __tmp.len();
18792 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18793 } else {
18794 __tmp.len()
18795 }
18796 }
18797}
18798#[doc = "id: 44"]
18799#[doc = "This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints."]
18800#[derive(Debug, Clone, PartialEq)]
18801#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18802#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18803pub struct MISSION_COUNT_DATA {
18804 #[doc = "Number of mission items in the sequence"]
18805 pub count: u16,
18806 #[doc = "System ID"]
18807 pub target_system: u8,
18808 #[doc = "Component ID"]
18809 pub target_component: u8,
18810 #[doc = "Mission type."]
18811 #[cfg_attr(feature = "serde", serde(default))]
18812 pub mission_type: MavMissionType,
18813 #[doc = "Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle). This field is used when downloading a plan from a vehicle to a GCS. 0 on upload to the vehicle from GCS. 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK)."]
18814 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18815 pub opaque_id: u32,
18816}
18817impl MISSION_COUNT_DATA {
18818 pub const ENCODED_LEN: usize = 9usize;
18819 pub const DEFAULT: Self = Self {
18820 count: 0_u16,
18821 target_system: 0_u8,
18822 target_component: 0_u8,
18823 mission_type: MavMissionType::DEFAULT,
18824 opaque_id: 0_u32,
18825 };
18826 #[cfg(feature = "arbitrary")]
18827 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18828 use arbitrary::{Arbitrary, Unstructured};
18829 let mut buf = [0u8; 1024];
18830 rng.fill_bytes(&mut buf);
18831 let mut unstructured = Unstructured::new(&buf);
18832 Self::arbitrary(&mut unstructured).unwrap_or_default()
18833 }
18834}
18835impl Default for MISSION_COUNT_DATA {
18836 fn default() -> Self {
18837 Self::DEFAULT.clone()
18838 }
18839}
18840impl MessageData for MISSION_COUNT_DATA {
18841 type Message = MavMessage;
18842 const ID: u32 = 44u32;
18843 const NAME: &'static str = "MISSION_COUNT";
18844 const EXTRA_CRC: u8 = 221u8;
18845 const ENCODED_LEN: usize = 9usize;
18846 fn deser(
18847 _version: MavlinkVersion,
18848 __input: &[u8],
18849 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18850 let avail_len = __input.len();
18851 let mut payload_buf = [0; Self::ENCODED_LEN];
18852 let mut buf = if avail_len < Self::ENCODED_LEN {
18853 payload_buf[0..avail_len].copy_from_slice(__input);
18854 Bytes::new(&payload_buf)
18855 } else {
18856 Bytes::new(__input)
18857 };
18858 let mut __struct = Self::default();
18859 __struct.count = buf.get_u16_le();
18860 __struct.target_system = buf.get_u8();
18861 __struct.target_component = buf.get_u8();
18862 let tmp = buf.get_u8();
18863 __struct.mission_type =
18864 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18865 enum_type: "MavMissionType",
18866 value: tmp as u32,
18867 })?;
18868 __struct.opaque_id = buf.get_u32_le();
18869 Ok(__struct)
18870 }
18871 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18872 let mut __tmp = BytesMut::new(bytes);
18873 #[allow(clippy::absurd_extreme_comparisons)]
18874 #[allow(unused_comparisons)]
18875 if __tmp.remaining() < Self::ENCODED_LEN {
18876 panic!(
18877 "buffer is too small (need {} bytes, but got {})",
18878 Self::ENCODED_LEN,
18879 __tmp.remaining(),
18880 )
18881 }
18882 __tmp.put_u16_le(self.count);
18883 __tmp.put_u8(self.target_system);
18884 __tmp.put_u8(self.target_component);
18885 __tmp.put_u8(self.mission_type as u8);
18886 __tmp.put_u32_le(self.opaque_id);
18887 if matches!(version, MavlinkVersion::V2) {
18888 let len = __tmp.len();
18889 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18890 } else {
18891 __tmp.len()
18892 }
18893 }
18894}
18895#[doc = "id: 12918"]
18896#[doc = "Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm."]
18897#[derive(Debug, Clone, PartialEq)]
18898#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18899#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18900pub struct OPEN_DRONE_ID_ARM_STATUS_DATA {
18901 #[doc = "Status level indicating if arming is allowed."]
18902 pub status: MavOdidArmStatus,
18903 #[doc = "Text error message, should be empty if status is good to arm. Fill with nulls in unused portion."]
18904 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18905 pub error: [u8; 50],
18906}
18907impl OPEN_DRONE_ID_ARM_STATUS_DATA {
18908 pub const ENCODED_LEN: usize = 51usize;
18909 pub const DEFAULT: Self = Self {
18910 status: MavOdidArmStatus::DEFAULT,
18911 error: [0_u8; 50usize],
18912 };
18913 #[cfg(feature = "arbitrary")]
18914 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18915 use arbitrary::{Arbitrary, Unstructured};
18916 let mut buf = [0u8; 1024];
18917 rng.fill_bytes(&mut buf);
18918 let mut unstructured = Unstructured::new(&buf);
18919 Self::arbitrary(&mut unstructured).unwrap_or_default()
18920 }
18921}
18922impl Default for OPEN_DRONE_ID_ARM_STATUS_DATA {
18923 fn default() -> Self {
18924 Self::DEFAULT.clone()
18925 }
18926}
18927impl MessageData for OPEN_DRONE_ID_ARM_STATUS_DATA {
18928 type Message = MavMessage;
18929 const ID: u32 = 12918u32;
18930 const NAME: &'static str = "OPEN_DRONE_ID_ARM_STATUS";
18931 const EXTRA_CRC: u8 = 139u8;
18932 const ENCODED_LEN: usize = 51usize;
18933 fn deser(
18934 _version: MavlinkVersion,
18935 __input: &[u8],
18936 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18937 let avail_len = __input.len();
18938 let mut payload_buf = [0; Self::ENCODED_LEN];
18939 let mut buf = if avail_len < Self::ENCODED_LEN {
18940 payload_buf[0..avail_len].copy_from_slice(__input);
18941 Bytes::new(&payload_buf)
18942 } else {
18943 Bytes::new(__input)
18944 };
18945 let mut __struct = Self::default();
18946 let tmp = buf.get_u8();
18947 __struct.status =
18948 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18949 enum_type: "MavOdidArmStatus",
18950 value: tmp as u32,
18951 })?;
18952 for v in &mut __struct.error {
18953 let val = buf.get_u8();
18954 *v = val;
18955 }
18956 Ok(__struct)
18957 }
18958 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18959 let mut __tmp = BytesMut::new(bytes);
18960 #[allow(clippy::absurd_extreme_comparisons)]
18961 #[allow(unused_comparisons)]
18962 if __tmp.remaining() < Self::ENCODED_LEN {
18963 panic!(
18964 "buffer is too small (need {} bytes, but got {})",
18965 Self::ENCODED_LEN,
18966 __tmp.remaining(),
18967 )
18968 }
18969 __tmp.put_u8(self.status as u8);
18970 for val in &self.error {
18971 __tmp.put_u8(*val);
18972 }
18973 if matches!(version, MavlinkVersion::V2) {
18974 let len = __tmp.len();
18975 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18976 } else {
18977 __tmp.len()
18978 }
18979 }
18980}
18981#[doc = "id: 70"]
18982#[doc = "The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels."]
18983#[derive(Debug, Clone, PartialEq)]
18984#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18985#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18986pub struct RC_CHANNELS_OVERRIDE_DATA {
18987 #[doc = "RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
18988 pub chan1_raw: u16,
18989 #[doc = "RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
18990 pub chan2_raw: u16,
18991 #[doc = "RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
18992 pub chan3_raw: u16,
18993 #[doc = "RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
18994 pub chan4_raw: u16,
18995 #[doc = "RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
18996 pub chan5_raw: u16,
18997 #[doc = "RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
18998 pub chan6_raw: u16,
18999 #[doc = "RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
19000 pub chan7_raw: u16,
19001 #[doc = "RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
19002 pub chan8_raw: u16,
19003 #[doc = "System ID"]
19004 pub target_system: u8,
19005 #[doc = "Component ID"]
19006 pub target_component: u8,
19007 #[doc = "RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
19008 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19009 pub chan9_raw: u16,
19010 #[doc = "RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
19011 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19012 pub chan10_raw: u16,
19013 #[doc = "RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
19014 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19015 pub chan11_raw: u16,
19016 #[doc = "RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
19017 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19018 pub chan12_raw: u16,
19019 #[doc = "RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
19020 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19021 pub chan13_raw: u16,
19022 #[doc = "RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
19023 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19024 pub chan14_raw: u16,
19025 #[doc = "RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
19026 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19027 pub chan15_raw: u16,
19028 #[doc = "RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
19029 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19030 pub chan16_raw: u16,
19031 #[doc = "RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
19032 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19033 pub chan17_raw: u16,
19034 #[doc = "RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
19035 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19036 pub chan18_raw: u16,
19037}
19038impl RC_CHANNELS_OVERRIDE_DATA {
19039 pub const ENCODED_LEN: usize = 38usize;
19040 pub const DEFAULT: Self = Self {
19041 chan1_raw: 0_u16,
19042 chan2_raw: 0_u16,
19043 chan3_raw: 0_u16,
19044 chan4_raw: 0_u16,
19045 chan5_raw: 0_u16,
19046 chan6_raw: 0_u16,
19047 chan7_raw: 0_u16,
19048 chan8_raw: 0_u16,
19049 target_system: 0_u8,
19050 target_component: 0_u8,
19051 chan9_raw: 0_u16,
19052 chan10_raw: 0_u16,
19053 chan11_raw: 0_u16,
19054 chan12_raw: 0_u16,
19055 chan13_raw: 0_u16,
19056 chan14_raw: 0_u16,
19057 chan15_raw: 0_u16,
19058 chan16_raw: 0_u16,
19059 chan17_raw: 0_u16,
19060 chan18_raw: 0_u16,
19061 };
19062 #[cfg(feature = "arbitrary")]
19063 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19064 use arbitrary::{Arbitrary, Unstructured};
19065 let mut buf = [0u8; 1024];
19066 rng.fill_bytes(&mut buf);
19067 let mut unstructured = Unstructured::new(&buf);
19068 Self::arbitrary(&mut unstructured).unwrap_or_default()
19069 }
19070}
19071impl Default for RC_CHANNELS_OVERRIDE_DATA {
19072 fn default() -> Self {
19073 Self::DEFAULT.clone()
19074 }
19075}
19076impl MessageData for RC_CHANNELS_OVERRIDE_DATA {
19077 type Message = MavMessage;
19078 const ID: u32 = 70u32;
19079 const NAME: &'static str = "RC_CHANNELS_OVERRIDE";
19080 const EXTRA_CRC: u8 = 124u8;
19081 const ENCODED_LEN: usize = 38usize;
19082 fn deser(
19083 _version: MavlinkVersion,
19084 __input: &[u8],
19085 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19086 let avail_len = __input.len();
19087 let mut payload_buf = [0; Self::ENCODED_LEN];
19088 let mut buf = if avail_len < Self::ENCODED_LEN {
19089 payload_buf[0..avail_len].copy_from_slice(__input);
19090 Bytes::new(&payload_buf)
19091 } else {
19092 Bytes::new(__input)
19093 };
19094 let mut __struct = Self::default();
19095 __struct.chan1_raw = buf.get_u16_le();
19096 __struct.chan2_raw = buf.get_u16_le();
19097 __struct.chan3_raw = buf.get_u16_le();
19098 __struct.chan4_raw = buf.get_u16_le();
19099 __struct.chan5_raw = buf.get_u16_le();
19100 __struct.chan6_raw = buf.get_u16_le();
19101 __struct.chan7_raw = buf.get_u16_le();
19102 __struct.chan8_raw = buf.get_u16_le();
19103 __struct.target_system = buf.get_u8();
19104 __struct.target_component = buf.get_u8();
19105 __struct.chan9_raw = buf.get_u16_le();
19106 __struct.chan10_raw = buf.get_u16_le();
19107 __struct.chan11_raw = buf.get_u16_le();
19108 __struct.chan12_raw = buf.get_u16_le();
19109 __struct.chan13_raw = buf.get_u16_le();
19110 __struct.chan14_raw = buf.get_u16_le();
19111 __struct.chan15_raw = buf.get_u16_le();
19112 __struct.chan16_raw = buf.get_u16_le();
19113 __struct.chan17_raw = buf.get_u16_le();
19114 __struct.chan18_raw = buf.get_u16_le();
19115 Ok(__struct)
19116 }
19117 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19118 let mut __tmp = BytesMut::new(bytes);
19119 #[allow(clippy::absurd_extreme_comparisons)]
19120 #[allow(unused_comparisons)]
19121 if __tmp.remaining() < Self::ENCODED_LEN {
19122 panic!(
19123 "buffer is too small (need {} bytes, but got {})",
19124 Self::ENCODED_LEN,
19125 __tmp.remaining(),
19126 )
19127 }
19128 __tmp.put_u16_le(self.chan1_raw);
19129 __tmp.put_u16_le(self.chan2_raw);
19130 __tmp.put_u16_le(self.chan3_raw);
19131 __tmp.put_u16_le(self.chan4_raw);
19132 __tmp.put_u16_le(self.chan5_raw);
19133 __tmp.put_u16_le(self.chan6_raw);
19134 __tmp.put_u16_le(self.chan7_raw);
19135 __tmp.put_u16_le(self.chan8_raw);
19136 __tmp.put_u8(self.target_system);
19137 __tmp.put_u8(self.target_component);
19138 __tmp.put_u16_le(self.chan9_raw);
19139 __tmp.put_u16_le(self.chan10_raw);
19140 __tmp.put_u16_le(self.chan11_raw);
19141 __tmp.put_u16_le(self.chan12_raw);
19142 __tmp.put_u16_le(self.chan13_raw);
19143 __tmp.put_u16_le(self.chan14_raw);
19144 __tmp.put_u16_le(self.chan15_raw);
19145 __tmp.put_u16_le(self.chan16_raw);
19146 __tmp.put_u16_le(self.chan17_raw);
19147 __tmp.put_u16_le(self.chan18_raw);
19148 if matches!(version, MavlinkVersion::V2) {
19149 let len = __tmp.len();
19150 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19151 } else {
19152 __tmp.len()
19153 }
19154 }
19155}
19156#[doc = "id: 133"]
19157#[doc = "Request for terrain data and terrain status. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
19158#[derive(Debug, Clone, PartialEq)]
19159#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19160#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19161pub struct TERRAIN_REQUEST_DATA {
19162 #[doc = "Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)"]
19163 pub mask: u64,
19164 #[doc = "Latitude of SW corner of first grid"]
19165 pub lat: i32,
19166 #[doc = "Longitude of SW corner of first grid"]
19167 pub lon: i32,
19168 #[doc = "Grid spacing"]
19169 pub grid_spacing: u16,
19170}
19171impl TERRAIN_REQUEST_DATA {
19172 pub const ENCODED_LEN: usize = 18usize;
19173 pub const DEFAULT: Self = Self {
19174 mask: 0_u64,
19175 lat: 0_i32,
19176 lon: 0_i32,
19177 grid_spacing: 0_u16,
19178 };
19179 #[cfg(feature = "arbitrary")]
19180 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19181 use arbitrary::{Arbitrary, Unstructured};
19182 let mut buf = [0u8; 1024];
19183 rng.fill_bytes(&mut buf);
19184 let mut unstructured = Unstructured::new(&buf);
19185 Self::arbitrary(&mut unstructured).unwrap_or_default()
19186 }
19187}
19188impl Default for TERRAIN_REQUEST_DATA {
19189 fn default() -> Self {
19190 Self::DEFAULT.clone()
19191 }
19192}
19193impl MessageData for TERRAIN_REQUEST_DATA {
19194 type Message = MavMessage;
19195 const ID: u32 = 133u32;
19196 const NAME: &'static str = "TERRAIN_REQUEST";
19197 const EXTRA_CRC: u8 = 6u8;
19198 const ENCODED_LEN: usize = 18usize;
19199 fn deser(
19200 _version: MavlinkVersion,
19201 __input: &[u8],
19202 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19203 let avail_len = __input.len();
19204 let mut payload_buf = [0; Self::ENCODED_LEN];
19205 let mut buf = if avail_len < Self::ENCODED_LEN {
19206 payload_buf[0..avail_len].copy_from_slice(__input);
19207 Bytes::new(&payload_buf)
19208 } else {
19209 Bytes::new(__input)
19210 };
19211 let mut __struct = Self::default();
19212 __struct.mask = buf.get_u64_le();
19213 __struct.lat = buf.get_i32_le();
19214 __struct.lon = buf.get_i32_le();
19215 __struct.grid_spacing = buf.get_u16_le();
19216 Ok(__struct)
19217 }
19218 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19219 let mut __tmp = BytesMut::new(bytes);
19220 #[allow(clippy::absurd_extreme_comparisons)]
19221 #[allow(unused_comparisons)]
19222 if __tmp.remaining() < Self::ENCODED_LEN {
19223 panic!(
19224 "buffer is too small (need {} bytes, but got {})",
19225 Self::ENCODED_LEN,
19226 __tmp.remaining(),
19227 )
19228 }
19229 __tmp.put_u64_le(self.mask);
19230 __tmp.put_i32_le(self.lat);
19231 __tmp.put_i32_le(self.lon);
19232 __tmp.put_u16_le(self.grid_spacing);
19233 if matches!(version, MavlinkVersion::V2) {
19234 let len = __tmp.len();
19235 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19236 } else {
19237 __tmp.len()
19238 }
19239 }
19240}
19241#[doc = "id: 330"]
19242#[doc = "Obstacle distances in front of the sensor, starting from the left in increment degrees to the right."]
19243#[derive(Debug, Clone, PartialEq)]
19244#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19245#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19246pub struct OBSTACLE_DISTANCE_DATA {
19247 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19248 pub time_usec: u64,
19249 #[doc = "Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm."]
19250 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19251 pub distances: [u16; 72],
19252 #[doc = "Minimum distance the sensor can measure."]
19253 pub min_distance: u16,
19254 #[doc = "Maximum distance the sensor can measure."]
19255 pub max_distance: u16,
19256 #[doc = "Class id of the distance sensor type."]
19257 pub sensor_type: MavDistanceSensor,
19258 #[doc = "Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero."]
19259 pub increment: u8,
19260 #[doc = "Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise."]
19261 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19262 pub increment_f: f32,
19263 #[doc = "Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise."]
19264 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19265 pub angle_offset: f32,
19266 #[doc = "Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned."]
19267 #[cfg_attr(feature = "serde", serde(default))]
19268 pub frame: MavFrame,
19269}
19270impl OBSTACLE_DISTANCE_DATA {
19271 pub const ENCODED_LEN: usize = 167usize;
19272 pub const DEFAULT: Self = Self {
19273 time_usec: 0_u64,
19274 distances: [0_u16; 72usize],
19275 min_distance: 0_u16,
19276 max_distance: 0_u16,
19277 sensor_type: MavDistanceSensor::DEFAULT,
19278 increment: 0_u8,
19279 increment_f: 0.0_f32,
19280 angle_offset: 0.0_f32,
19281 frame: MavFrame::DEFAULT,
19282 };
19283 #[cfg(feature = "arbitrary")]
19284 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19285 use arbitrary::{Arbitrary, Unstructured};
19286 let mut buf = [0u8; 1024];
19287 rng.fill_bytes(&mut buf);
19288 let mut unstructured = Unstructured::new(&buf);
19289 Self::arbitrary(&mut unstructured).unwrap_or_default()
19290 }
19291}
19292impl Default for OBSTACLE_DISTANCE_DATA {
19293 fn default() -> Self {
19294 Self::DEFAULT.clone()
19295 }
19296}
19297impl MessageData for OBSTACLE_DISTANCE_DATA {
19298 type Message = MavMessage;
19299 const ID: u32 = 330u32;
19300 const NAME: &'static str = "OBSTACLE_DISTANCE";
19301 const EXTRA_CRC: u8 = 23u8;
19302 const ENCODED_LEN: usize = 167usize;
19303 fn deser(
19304 _version: MavlinkVersion,
19305 __input: &[u8],
19306 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19307 let avail_len = __input.len();
19308 let mut payload_buf = [0; Self::ENCODED_LEN];
19309 let mut buf = if avail_len < Self::ENCODED_LEN {
19310 payload_buf[0..avail_len].copy_from_slice(__input);
19311 Bytes::new(&payload_buf)
19312 } else {
19313 Bytes::new(__input)
19314 };
19315 let mut __struct = Self::default();
19316 __struct.time_usec = buf.get_u64_le();
19317 for v in &mut __struct.distances {
19318 let val = buf.get_u16_le();
19319 *v = val;
19320 }
19321 __struct.min_distance = buf.get_u16_le();
19322 __struct.max_distance = buf.get_u16_le();
19323 let tmp = buf.get_u8();
19324 __struct.sensor_type =
19325 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19326 enum_type: "MavDistanceSensor",
19327 value: tmp as u32,
19328 })?;
19329 __struct.increment = buf.get_u8();
19330 __struct.increment_f = buf.get_f32_le();
19331 __struct.angle_offset = buf.get_f32_le();
19332 let tmp = buf.get_u8();
19333 __struct.frame =
19334 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19335 enum_type: "MavFrame",
19336 value: tmp as u32,
19337 })?;
19338 Ok(__struct)
19339 }
19340 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19341 let mut __tmp = BytesMut::new(bytes);
19342 #[allow(clippy::absurd_extreme_comparisons)]
19343 #[allow(unused_comparisons)]
19344 if __tmp.remaining() < Self::ENCODED_LEN {
19345 panic!(
19346 "buffer is too small (need {} bytes, but got {})",
19347 Self::ENCODED_LEN,
19348 __tmp.remaining(),
19349 )
19350 }
19351 __tmp.put_u64_le(self.time_usec);
19352 for val in &self.distances {
19353 __tmp.put_u16_le(*val);
19354 }
19355 __tmp.put_u16_le(self.min_distance);
19356 __tmp.put_u16_le(self.max_distance);
19357 __tmp.put_u8(self.sensor_type as u8);
19358 __tmp.put_u8(self.increment);
19359 __tmp.put_f32_le(self.increment_f);
19360 __tmp.put_f32_le(self.angle_offset);
19361 __tmp.put_u8(self.frame as u8);
19362 if matches!(version, MavlinkVersion::V2) {
19363 let len = __tmp.len();
19364 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19365 } else {
19366 __tmp.len()
19367 }
19368 }
19369}
19370#[doc = "id: 149"]
19371#[doc = "The location of a landing target. See: <https://mavlink.io/en/services/landing_target.html>."]
19372#[derive(Debug, Clone, PartialEq)]
19373#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19374#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19375pub struct LANDING_TARGET_DATA {
19376 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19377 pub time_usec: u64,
19378 #[doc = "X-axis angular offset of the target from the center of the image"]
19379 pub angle_x: f32,
19380 #[doc = "Y-axis angular offset of the target from the center of the image"]
19381 pub angle_y: f32,
19382 #[doc = "Distance to the target from the vehicle"]
19383 pub distance: f32,
19384 #[doc = "Size of target along x-axis"]
19385 pub size_x: f32,
19386 #[doc = "Size of target along y-axis"]
19387 pub size_y: f32,
19388 #[doc = "The ID of the target if multiple targets are present"]
19389 pub target_num: u8,
19390 #[doc = "Coordinate frame used for following fields."]
19391 pub frame: MavFrame,
19392 #[doc = "X Position of the landing target in MAV_FRAME"]
19393 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19394 pub x: f32,
19395 #[doc = "Y Position of the landing target in MAV_FRAME"]
19396 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19397 pub y: f32,
19398 #[doc = "Z Position of the landing target in MAV_FRAME"]
19399 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19400 pub z: f32,
19401 #[doc = "Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
19402 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19403 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19404 pub q: [f32; 4],
19405 #[doc = "Type of landing target"]
19406 #[cfg_attr(feature = "serde", serde(default))]
19407 pub mavtype: LandingTargetType,
19408 #[doc = "Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid)."]
19409 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19410 pub position_valid: u8,
19411}
19412impl LANDING_TARGET_DATA {
19413 pub const ENCODED_LEN: usize = 60usize;
19414 pub const DEFAULT: Self = Self {
19415 time_usec: 0_u64,
19416 angle_x: 0.0_f32,
19417 angle_y: 0.0_f32,
19418 distance: 0.0_f32,
19419 size_x: 0.0_f32,
19420 size_y: 0.0_f32,
19421 target_num: 0_u8,
19422 frame: MavFrame::DEFAULT,
19423 x: 0.0_f32,
19424 y: 0.0_f32,
19425 z: 0.0_f32,
19426 q: [0.0_f32; 4usize],
19427 mavtype: LandingTargetType::DEFAULT,
19428 position_valid: 0_u8,
19429 };
19430 #[cfg(feature = "arbitrary")]
19431 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19432 use arbitrary::{Arbitrary, Unstructured};
19433 let mut buf = [0u8; 1024];
19434 rng.fill_bytes(&mut buf);
19435 let mut unstructured = Unstructured::new(&buf);
19436 Self::arbitrary(&mut unstructured).unwrap_or_default()
19437 }
19438}
19439impl Default for LANDING_TARGET_DATA {
19440 fn default() -> Self {
19441 Self::DEFAULT.clone()
19442 }
19443}
19444impl MessageData for LANDING_TARGET_DATA {
19445 type Message = MavMessage;
19446 const ID: u32 = 149u32;
19447 const NAME: &'static str = "LANDING_TARGET";
19448 const EXTRA_CRC: u8 = 200u8;
19449 const ENCODED_LEN: usize = 60usize;
19450 fn deser(
19451 _version: MavlinkVersion,
19452 __input: &[u8],
19453 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19454 let avail_len = __input.len();
19455 let mut payload_buf = [0; Self::ENCODED_LEN];
19456 let mut buf = if avail_len < Self::ENCODED_LEN {
19457 payload_buf[0..avail_len].copy_from_slice(__input);
19458 Bytes::new(&payload_buf)
19459 } else {
19460 Bytes::new(__input)
19461 };
19462 let mut __struct = Self::default();
19463 __struct.time_usec = buf.get_u64_le();
19464 __struct.angle_x = buf.get_f32_le();
19465 __struct.angle_y = buf.get_f32_le();
19466 __struct.distance = buf.get_f32_le();
19467 __struct.size_x = buf.get_f32_le();
19468 __struct.size_y = buf.get_f32_le();
19469 __struct.target_num = buf.get_u8();
19470 let tmp = buf.get_u8();
19471 __struct.frame =
19472 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19473 enum_type: "MavFrame",
19474 value: tmp as u32,
19475 })?;
19476 __struct.x = buf.get_f32_le();
19477 __struct.y = buf.get_f32_le();
19478 __struct.z = buf.get_f32_le();
19479 for v in &mut __struct.q {
19480 let val = buf.get_f32_le();
19481 *v = val;
19482 }
19483 let tmp = buf.get_u8();
19484 __struct.mavtype =
19485 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19486 enum_type: "LandingTargetType",
19487 value: tmp as u32,
19488 })?;
19489 __struct.position_valid = buf.get_u8();
19490 Ok(__struct)
19491 }
19492 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19493 let mut __tmp = BytesMut::new(bytes);
19494 #[allow(clippy::absurd_extreme_comparisons)]
19495 #[allow(unused_comparisons)]
19496 if __tmp.remaining() < Self::ENCODED_LEN {
19497 panic!(
19498 "buffer is too small (need {} bytes, but got {})",
19499 Self::ENCODED_LEN,
19500 __tmp.remaining(),
19501 )
19502 }
19503 __tmp.put_u64_le(self.time_usec);
19504 __tmp.put_f32_le(self.angle_x);
19505 __tmp.put_f32_le(self.angle_y);
19506 __tmp.put_f32_le(self.distance);
19507 __tmp.put_f32_le(self.size_x);
19508 __tmp.put_f32_le(self.size_y);
19509 __tmp.put_u8(self.target_num);
19510 __tmp.put_u8(self.frame as u8);
19511 __tmp.put_f32_le(self.x);
19512 __tmp.put_f32_le(self.y);
19513 __tmp.put_f32_le(self.z);
19514 for val in &self.q {
19515 __tmp.put_f32_le(*val);
19516 }
19517 __tmp.put_u8(self.mavtype as u8);
19518 __tmp.put_u8(self.position_valid);
19519 if matches!(version, MavlinkVersion::V2) {
19520 let len = __tmp.len();
19521 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19522 } else {
19523 __tmp.len()
19524 }
19525 }
19526}
19527#[doc = "id: 144"]
19528#[doc = "Current motion information from a designated system."]
19529#[derive(Debug, Clone, PartialEq)]
19530#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19531#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19532pub struct FOLLOW_TARGET_DATA {
19533 #[doc = "Timestamp (time since system boot)."]
19534 pub timestamp: u64,
19535 #[doc = "button states or switches of a tracker device"]
19536 pub custom_state: u64,
19537 #[doc = "Latitude (WGS84)"]
19538 pub lat: i32,
19539 #[doc = "Longitude (WGS84)"]
19540 pub lon: i32,
19541 #[doc = "Altitude (MSL)"]
19542 pub alt: f32,
19543 #[doc = "target velocity (0,0,0) for unknown"]
19544 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19545 pub vel: [f32; 3],
19546 #[doc = "linear target acceleration (0,0,0) for unknown"]
19547 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19548 pub acc: [f32; 3],
19549 #[doc = "(0 0 0 0 for unknown)"]
19550 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19551 pub attitude_q: [f32; 4],
19552 #[doc = "(0 0 0 for unknown)"]
19553 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19554 pub rates: [f32; 3],
19555 #[doc = "eph epv"]
19556 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19557 pub position_cov: [f32; 3],
19558 #[doc = "bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)"]
19559 pub est_capabilities: u8,
19560}
19561impl FOLLOW_TARGET_DATA {
19562 pub const ENCODED_LEN: usize = 93usize;
19563 pub const DEFAULT: Self = Self {
19564 timestamp: 0_u64,
19565 custom_state: 0_u64,
19566 lat: 0_i32,
19567 lon: 0_i32,
19568 alt: 0.0_f32,
19569 vel: [0.0_f32; 3usize],
19570 acc: [0.0_f32; 3usize],
19571 attitude_q: [0.0_f32; 4usize],
19572 rates: [0.0_f32; 3usize],
19573 position_cov: [0.0_f32; 3usize],
19574 est_capabilities: 0_u8,
19575 };
19576 #[cfg(feature = "arbitrary")]
19577 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19578 use arbitrary::{Arbitrary, Unstructured};
19579 let mut buf = [0u8; 1024];
19580 rng.fill_bytes(&mut buf);
19581 let mut unstructured = Unstructured::new(&buf);
19582 Self::arbitrary(&mut unstructured).unwrap_or_default()
19583 }
19584}
19585impl Default for FOLLOW_TARGET_DATA {
19586 fn default() -> Self {
19587 Self::DEFAULT.clone()
19588 }
19589}
19590impl MessageData for FOLLOW_TARGET_DATA {
19591 type Message = MavMessage;
19592 const ID: u32 = 144u32;
19593 const NAME: &'static str = "FOLLOW_TARGET";
19594 const EXTRA_CRC: u8 = 127u8;
19595 const ENCODED_LEN: usize = 93usize;
19596 fn deser(
19597 _version: MavlinkVersion,
19598 __input: &[u8],
19599 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19600 let avail_len = __input.len();
19601 let mut payload_buf = [0; Self::ENCODED_LEN];
19602 let mut buf = if avail_len < Self::ENCODED_LEN {
19603 payload_buf[0..avail_len].copy_from_slice(__input);
19604 Bytes::new(&payload_buf)
19605 } else {
19606 Bytes::new(__input)
19607 };
19608 let mut __struct = Self::default();
19609 __struct.timestamp = buf.get_u64_le();
19610 __struct.custom_state = buf.get_u64_le();
19611 __struct.lat = buf.get_i32_le();
19612 __struct.lon = buf.get_i32_le();
19613 __struct.alt = buf.get_f32_le();
19614 for v in &mut __struct.vel {
19615 let val = buf.get_f32_le();
19616 *v = val;
19617 }
19618 for v in &mut __struct.acc {
19619 let val = buf.get_f32_le();
19620 *v = val;
19621 }
19622 for v in &mut __struct.attitude_q {
19623 let val = buf.get_f32_le();
19624 *v = val;
19625 }
19626 for v in &mut __struct.rates {
19627 let val = buf.get_f32_le();
19628 *v = val;
19629 }
19630 for v in &mut __struct.position_cov {
19631 let val = buf.get_f32_le();
19632 *v = val;
19633 }
19634 __struct.est_capabilities = buf.get_u8();
19635 Ok(__struct)
19636 }
19637 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19638 let mut __tmp = BytesMut::new(bytes);
19639 #[allow(clippy::absurd_extreme_comparisons)]
19640 #[allow(unused_comparisons)]
19641 if __tmp.remaining() < Self::ENCODED_LEN {
19642 panic!(
19643 "buffer is too small (need {} bytes, but got {})",
19644 Self::ENCODED_LEN,
19645 __tmp.remaining(),
19646 )
19647 }
19648 __tmp.put_u64_le(self.timestamp);
19649 __tmp.put_u64_le(self.custom_state);
19650 __tmp.put_i32_le(self.lat);
19651 __tmp.put_i32_le(self.lon);
19652 __tmp.put_f32_le(self.alt);
19653 for val in &self.vel {
19654 __tmp.put_f32_le(*val);
19655 }
19656 for val in &self.acc {
19657 __tmp.put_f32_le(*val);
19658 }
19659 for val in &self.attitude_q {
19660 __tmp.put_f32_le(*val);
19661 }
19662 for val in &self.rates {
19663 __tmp.put_f32_le(*val);
19664 }
19665 for val in &self.position_cov {
19666 __tmp.put_f32_le(*val);
19667 }
19668 __tmp.put_u8(self.est_capabilities);
19669 if matches!(version, MavlinkVersion::V2) {
19670 let len = __tmp.len();
19671 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19672 } else {
19673 __tmp.len()
19674 }
19675 }
19676}
19677#[doc = "id: 63"]
19678#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset."]
19679#[derive(Debug, Clone, PartialEq)]
19680#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19681#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19682pub struct GLOBAL_POSITION_INT_COV_DATA {
19683 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19684 pub time_usec: u64,
19685 #[doc = "Latitude"]
19686 pub lat: i32,
19687 #[doc = "Longitude"]
19688 pub lon: i32,
19689 #[doc = "Altitude in meters above MSL"]
19690 pub alt: i32,
19691 #[doc = "Altitude above ground"]
19692 pub relative_alt: i32,
19693 #[doc = "Ground X Speed (Latitude)"]
19694 pub vx: f32,
19695 #[doc = "Ground Y Speed (Longitude)"]
19696 pub vy: f32,
19697 #[doc = "Ground Z Speed (Altitude)"]
19698 pub vz: f32,
19699 #[doc = "Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
19700 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19701 pub covariance: [f32; 36],
19702 #[doc = "Class id of the estimator this estimate originated from."]
19703 pub estimator_type: MavEstimatorType,
19704}
19705impl GLOBAL_POSITION_INT_COV_DATA {
19706 pub const ENCODED_LEN: usize = 181usize;
19707 pub const DEFAULT: Self = Self {
19708 time_usec: 0_u64,
19709 lat: 0_i32,
19710 lon: 0_i32,
19711 alt: 0_i32,
19712 relative_alt: 0_i32,
19713 vx: 0.0_f32,
19714 vy: 0.0_f32,
19715 vz: 0.0_f32,
19716 covariance: [0.0_f32; 36usize],
19717 estimator_type: MavEstimatorType::DEFAULT,
19718 };
19719 #[cfg(feature = "arbitrary")]
19720 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19721 use arbitrary::{Arbitrary, Unstructured};
19722 let mut buf = [0u8; 1024];
19723 rng.fill_bytes(&mut buf);
19724 let mut unstructured = Unstructured::new(&buf);
19725 Self::arbitrary(&mut unstructured).unwrap_or_default()
19726 }
19727}
19728impl Default for GLOBAL_POSITION_INT_COV_DATA {
19729 fn default() -> Self {
19730 Self::DEFAULT.clone()
19731 }
19732}
19733impl MessageData for GLOBAL_POSITION_INT_COV_DATA {
19734 type Message = MavMessage;
19735 const ID: u32 = 63u32;
19736 const NAME: &'static str = "GLOBAL_POSITION_INT_COV";
19737 const EXTRA_CRC: u8 = 119u8;
19738 const ENCODED_LEN: usize = 181usize;
19739 fn deser(
19740 _version: MavlinkVersion,
19741 __input: &[u8],
19742 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19743 let avail_len = __input.len();
19744 let mut payload_buf = [0; Self::ENCODED_LEN];
19745 let mut buf = if avail_len < Self::ENCODED_LEN {
19746 payload_buf[0..avail_len].copy_from_slice(__input);
19747 Bytes::new(&payload_buf)
19748 } else {
19749 Bytes::new(__input)
19750 };
19751 let mut __struct = Self::default();
19752 __struct.time_usec = buf.get_u64_le();
19753 __struct.lat = buf.get_i32_le();
19754 __struct.lon = buf.get_i32_le();
19755 __struct.alt = buf.get_i32_le();
19756 __struct.relative_alt = buf.get_i32_le();
19757 __struct.vx = buf.get_f32_le();
19758 __struct.vy = buf.get_f32_le();
19759 __struct.vz = buf.get_f32_le();
19760 for v in &mut __struct.covariance {
19761 let val = buf.get_f32_le();
19762 *v = val;
19763 }
19764 let tmp = buf.get_u8();
19765 __struct.estimator_type =
19766 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
19767 enum_type: "MavEstimatorType",
19768 value: tmp as u32,
19769 })?;
19770 Ok(__struct)
19771 }
19772 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19773 let mut __tmp = BytesMut::new(bytes);
19774 #[allow(clippy::absurd_extreme_comparisons)]
19775 #[allow(unused_comparisons)]
19776 if __tmp.remaining() < Self::ENCODED_LEN {
19777 panic!(
19778 "buffer is too small (need {} bytes, but got {})",
19779 Self::ENCODED_LEN,
19780 __tmp.remaining(),
19781 )
19782 }
19783 __tmp.put_u64_le(self.time_usec);
19784 __tmp.put_i32_le(self.lat);
19785 __tmp.put_i32_le(self.lon);
19786 __tmp.put_i32_le(self.alt);
19787 __tmp.put_i32_le(self.relative_alt);
19788 __tmp.put_f32_le(self.vx);
19789 __tmp.put_f32_le(self.vy);
19790 __tmp.put_f32_le(self.vz);
19791 for val in &self.covariance {
19792 __tmp.put_f32_le(*val);
19793 }
19794 __tmp.put_u8(self.estimator_type as u8);
19795 if matches!(version, MavlinkVersion::V2) {
19796 let len = __tmp.len();
19797 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19798 } else {
19799 __tmp.len()
19800 }
19801 }
19802}
19803#[doc = "id: 146"]
19804#[doc = "The smoothed, monotonic system state used to feed the control loops of the system."]
19805#[derive(Debug, Clone, PartialEq)]
19806#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19807#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19808pub struct CONTROL_SYSTEM_STATE_DATA {
19809 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19810 pub time_usec: u64,
19811 #[doc = "X acceleration in body frame"]
19812 pub x_acc: f32,
19813 #[doc = "Y acceleration in body frame"]
19814 pub y_acc: f32,
19815 #[doc = "Z acceleration in body frame"]
19816 pub z_acc: f32,
19817 #[doc = "X velocity in body frame"]
19818 pub x_vel: f32,
19819 #[doc = "Y velocity in body frame"]
19820 pub y_vel: f32,
19821 #[doc = "Z velocity in body frame"]
19822 pub z_vel: f32,
19823 #[doc = "X position in local frame"]
19824 pub x_pos: f32,
19825 #[doc = "Y position in local frame"]
19826 pub y_pos: f32,
19827 #[doc = "Z position in local frame"]
19828 pub z_pos: f32,
19829 #[doc = "Airspeed, set to -1 if unknown"]
19830 pub airspeed: f32,
19831 #[doc = "Variance of body velocity estimate"]
19832 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19833 pub vel_variance: [f32; 3],
19834 #[doc = "Variance in local position"]
19835 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19836 pub pos_variance: [f32; 3],
19837 #[doc = "The attitude, represented as Quaternion"]
19838 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19839 pub q: [f32; 4],
19840 #[doc = "Angular rate in roll axis"]
19841 pub roll_rate: f32,
19842 #[doc = "Angular rate in pitch axis"]
19843 pub pitch_rate: f32,
19844 #[doc = "Angular rate in yaw axis"]
19845 pub yaw_rate: f32,
19846}
19847impl CONTROL_SYSTEM_STATE_DATA {
19848 pub const ENCODED_LEN: usize = 100usize;
19849 pub const DEFAULT: Self = Self {
19850 time_usec: 0_u64,
19851 x_acc: 0.0_f32,
19852 y_acc: 0.0_f32,
19853 z_acc: 0.0_f32,
19854 x_vel: 0.0_f32,
19855 y_vel: 0.0_f32,
19856 z_vel: 0.0_f32,
19857 x_pos: 0.0_f32,
19858 y_pos: 0.0_f32,
19859 z_pos: 0.0_f32,
19860 airspeed: 0.0_f32,
19861 vel_variance: [0.0_f32; 3usize],
19862 pos_variance: [0.0_f32; 3usize],
19863 q: [0.0_f32; 4usize],
19864 roll_rate: 0.0_f32,
19865 pitch_rate: 0.0_f32,
19866 yaw_rate: 0.0_f32,
19867 };
19868 #[cfg(feature = "arbitrary")]
19869 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19870 use arbitrary::{Arbitrary, Unstructured};
19871 let mut buf = [0u8; 1024];
19872 rng.fill_bytes(&mut buf);
19873 let mut unstructured = Unstructured::new(&buf);
19874 Self::arbitrary(&mut unstructured).unwrap_or_default()
19875 }
19876}
19877impl Default for CONTROL_SYSTEM_STATE_DATA {
19878 fn default() -> Self {
19879 Self::DEFAULT.clone()
19880 }
19881}
19882impl MessageData for CONTROL_SYSTEM_STATE_DATA {
19883 type Message = MavMessage;
19884 const ID: u32 = 146u32;
19885 const NAME: &'static str = "CONTROL_SYSTEM_STATE";
19886 const EXTRA_CRC: u8 = 103u8;
19887 const ENCODED_LEN: usize = 100usize;
19888 fn deser(
19889 _version: MavlinkVersion,
19890 __input: &[u8],
19891 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19892 let avail_len = __input.len();
19893 let mut payload_buf = [0; Self::ENCODED_LEN];
19894 let mut buf = if avail_len < Self::ENCODED_LEN {
19895 payload_buf[0..avail_len].copy_from_slice(__input);
19896 Bytes::new(&payload_buf)
19897 } else {
19898 Bytes::new(__input)
19899 };
19900 let mut __struct = Self::default();
19901 __struct.time_usec = buf.get_u64_le();
19902 __struct.x_acc = buf.get_f32_le();
19903 __struct.y_acc = buf.get_f32_le();
19904 __struct.z_acc = buf.get_f32_le();
19905 __struct.x_vel = buf.get_f32_le();
19906 __struct.y_vel = buf.get_f32_le();
19907 __struct.z_vel = buf.get_f32_le();
19908 __struct.x_pos = buf.get_f32_le();
19909 __struct.y_pos = buf.get_f32_le();
19910 __struct.z_pos = buf.get_f32_le();
19911 __struct.airspeed = buf.get_f32_le();
19912 for v in &mut __struct.vel_variance {
19913 let val = buf.get_f32_le();
19914 *v = val;
19915 }
19916 for v in &mut __struct.pos_variance {
19917 let val = buf.get_f32_le();
19918 *v = val;
19919 }
19920 for v in &mut __struct.q {
19921 let val = buf.get_f32_le();
19922 *v = val;
19923 }
19924 __struct.roll_rate = buf.get_f32_le();
19925 __struct.pitch_rate = buf.get_f32_le();
19926 __struct.yaw_rate = buf.get_f32_le();
19927 Ok(__struct)
19928 }
19929 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19930 let mut __tmp = BytesMut::new(bytes);
19931 #[allow(clippy::absurd_extreme_comparisons)]
19932 #[allow(unused_comparisons)]
19933 if __tmp.remaining() < Self::ENCODED_LEN {
19934 panic!(
19935 "buffer is too small (need {} bytes, but got {})",
19936 Self::ENCODED_LEN,
19937 __tmp.remaining(),
19938 )
19939 }
19940 __tmp.put_u64_le(self.time_usec);
19941 __tmp.put_f32_le(self.x_acc);
19942 __tmp.put_f32_le(self.y_acc);
19943 __tmp.put_f32_le(self.z_acc);
19944 __tmp.put_f32_le(self.x_vel);
19945 __tmp.put_f32_le(self.y_vel);
19946 __tmp.put_f32_le(self.z_vel);
19947 __tmp.put_f32_le(self.x_pos);
19948 __tmp.put_f32_le(self.y_pos);
19949 __tmp.put_f32_le(self.z_pos);
19950 __tmp.put_f32_le(self.airspeed);
19951 for val in &self.vel_variance {
19952 __tmp.put_f32_le(*val);
19953 }
19954 for val in &self.pos_variance {
19955 __tmp.put_f32_le(*val);
19956 }
19957 for val in &self.q {
19958 __tmp.put_f32_le(*val);
19959 }
19960 __tmp.put_f32_le(self.roll_rate);
19961 __tmp.put_f32_le(self.pitch_rate);
19962 __tmp.put_f32_le(self.yaw_rate);
19963 if matches!(version, MavlinkVersion::V2) {
19964 let len = __tmp.len();
19965 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19966 } else {
19967 __tmp.len()
19968 }
19969 }
19970}
19971#[doc = "id: 232"]
19972#[doc = "GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system."]
19973#[derive(Debug, Clone, PartialEq)]
19974#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19975#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19976pub struct GPS_INPUT_DATA {
19977 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19978 pub time_usec: u64,
19979 #[doc = "GPS time (from start of GPS week)"]
19980 pub time_week_ms: u32,
19981 #[doc = "Latitude (WGS84)"]
19982 pub lat: i32,
19983 #[doc = "Longitude (WGS84)"]
19984 pub lon: i32,
19985 #[doc = "Altitude (MSL). Positive for up."]
19986 pub alt: f32,
19987 #[doc = "GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX"]
19988 pub hdop: f32,
19989 #[doc = "GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX"]
19990 pub vdop: f32,
19991 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
19992 pub vn: f32,
19993 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
19994 pub ve: f32,
19995 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
19996 pub vd: f32,
19997 #[doc = "GPS speed accuracy"]
19998 pub speed_accuracy: f32,
19999 #[doc = "GPS horizontal accuracy"]
20000 pub horiz_accuracy: f32,
20001 #[doc = "GPS vertical accuracy"]
20002 pub vert_accuracy: f32,
20003 #[doc = "Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided."]
20004 pub ignore_flags: GpsInputIgnoreFlags,
20005 #[doc = "GPS week number"]
20006 pub time_week: u16,
20007 #[doc = "ID of the GPS for multiple GPS inputs"]
20008 pub gps_id: u8,
20009 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK"]
20010 pub fix_type: u8,
20011 #[doc = "Number of satellites visible."]
20012 pub satellites_visible: u8,
20013 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
20014 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20015 pub yaw: u16,
20016}
20017impl GPS_INPUT_DATA {
20018 pub const ENCODED_LEN: usize = 65usize;
20019 pub const DEFAULT: Self = Self {
20020 time_usec: 0_u64,
20021 time_week_ms: 0_u32,
20022 lat: 0_i32,
20023 lon: 0_i32,
20024 alt: 0.0_f32,
20025 hdop: 0.0_f32,
20026 vdop: 0.0_f32,
20027 vn: 0.0_f32,
20028 ve: 0.0_f32,
20029 vd: 0.0_f32,
20030 speed_accuracy: 0.0_f32,
20031 horiz_accuracy: 0.0_f32,
20032 vert_accuracy: 0.0_f32,
20033 ignore_flags: GpsInputIgnoreFlags::DEFAULT,
20034 time_week: 0_u16,
20035 gps_id: 0_u8,
20036 fix_type: 0_u8,
20037 satellites_visible: 0_u8,
20038 yaw: 0_u16,
20039 };
20040 #[cfg(feature = "arbitrary")]
20041 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20042 use arbitrary::{Arbitrary, Unstructured};
20043 let mut buf = [0u8; 1024];
20044 rng.fill_bytes(&mut buf);
20045 let mut unstructured = Unstructured::new(&buf);
20046 Self::arbitrary(&mut unstructured).unwrap_or_default()
20047 }
20048}
20049impl Default for GPS_INPUT_DATA {
20050 fn default() -> Self {
20051 Self::DEFAULT.clone()
20052 }
20053}
20054impl MessageData for GPS_INPUT_DATA {
20055 type Message = MavMessage;
20056 const ID: u32 = 232u32;
20057 const NAME: &'static str = "GPS_INPUT";
20058 const EXTRA_CRC: u8 = 151u8;
20059 const ENCODED_LEN: usize = 65usize;
20060 fn deser(
20061 _version: MavlinkVersion,
20062 __input: &[u8],
20063 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20064 let avail_len = __input.len();
20065 let mut payload_buf = [0; Self::ENCODED_LEN];
20066 let mut buf = if avail_len < Self::ENCODED_LEN {
20067 payload_buf[0..avail_len].copy_from_slice(__input);
20068 Bytes::new(&payload_buf)
20069 } else {
20070 Bytes::new(__input)
20071 };
20072 let mut __struct = Self::default();
20073 __struct.time_usec = buf.get_u64_le();
20074 __struct.time_week_ms = buf.get_u32_le();
20075 __struct.lat = buf.get_i32_le();
20076 __struct.lon = buf.get_i32_le();
20077 __struct.alt = buf.get_f32_le();
20078 __struct.hdop = buf.get_f32_le();
20079 __struct.vdop = buf.get_f32_le();
20080 __struct.vn = buf.get_f32_le();
20081 __struct.ve = buf.get_f32_le();
20082 __struct.vd = buf.get_f32_le();
20083 __struct.speed_accuracy = buf.get_f32_le();
20084 __struct.horiz_accuracy = buf.get_f32_le();
20085 __struct.vert_accuracy = buf.get_f32_le();
20086 let tmp = buf.get_u16_le();
20087 __struct.ignore_flags = GpsInputIgnoreFlags::from_bits(
20088 tmp & GpsInputIgnoreFlags::all().bits(),
20089 )
20090 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
20091 flag_type: "GpsInputIgnoreFlags",
20092 value: tmp as u32,
20093 })?;
20094 __struct.time_week = buf.get_u16_le();
20095 __struct.gps_id = buf.get_u8();
20096 __struct.fix_type = buf.get_u8();
20097 __struct.satellites_visible = buf.get_u8();
20098 __struct.yaw = buf.get_u16_le();
20099 Ok(__struct)
20100 }
20101 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20102 let mut __tmp = BytesMut::new(bytes);
20103 #[allow(clippy::absurd_extreme_comparisons)]
20104 #[allow(unused_comparisons)]
20105 if __tmp.remaining() < Self::ENCODED_LEN {
20106 panic!(
20107 "buffer is too small (need {} bytes, but got {})",
20108 Self::ENCODED_LEN,
20109 __tmp.remaining(),
20110 )
20111 }
20112 __tmp.put_u64_le(self.time_usec);
20113 __tmp.put_u32_le(self.time_week_ms);
20114 __tmp.put_i32_le(self.lat);
20115 __tmp.put_i32_le(self.lon);
20116 __tmp.put_f32_le(self.alt);
20117 __tmp.put_f32_le(self.hdop);
20118 __tmp.put_f32_le(self.vdop);
20119 __tmp.put_f32_le(self.vn);
20120 __tmp.put_f32_le(self.ve);
20121 __tmp.put_f32_le(self.vd);
20122 __tmp.put_f32_le(self.speed_accuracy);
20123 __tmp.put_f32_le(self.horiz_accuracy);
20124 __tmp.put_f32_le(self.vert_accuracy);
20125 __tmp.put_u16_le(self.ignore_flags.bits());
20126 __tmp.put_u16_le(self.time_week);
20127 __tmp.put_u8(self.gps_id);
20128 __tmp.put_u8(self.fix_type);
20129 __tmp.put_u8(self.satellites_visible);
20130 __tmp.put_u16_le(self.yaw);
20131 if matches!(version, MavlinkVersion::V2) {
20132 let len = __tmp.len();
20133 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20134 } else {
20135 __tmp.len()
20136 }
20137 }
20138}
20139#[doc = "id: 258"]
20140#[doc = "Control vehicle tone generation (buzzer)."]
20141#[derive(Debug, Clone, PartialEq)]
20142#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20143#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20144pub struct PLAY_TUNE_DATA {
20145 #[doc = "System ID"]
20146 pub target_system: u8,
20147 #[doc = "Component ID"]
20148 pub target_component: u8,
20149 #[doc = "tune in board specific format"]
20150 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20151 pub tune: [u8; 30],
20152 #[doc = "tune extension (appended to tune)"]
20153 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20154 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20155 pub tune2: [u8; 200],
20156}
20157impl PLAY_TUNE_DATA {
20158 pub const ENCODED_LEN: usize = 232usize;
20159 pub const DEFAULT: Self = Self {
20160 target_system: 0_u8,
20161 target_component: 0_u8,
20162 tune: [0_u8; 30usize],
20163 tune2: [0_u8; 200usize],
20164 };
20165 #[cfg(feature = "arbitrary")]
20166 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20167 use arbitrary::{Arbitrary, Unstructured};
20168 let mut buf = [0u8; 1024];
20169 rng.fill_bytes(&mut buf);
20170 let mut unstructured = Unstructured::new(&buf);
20171 Self::arbitrary(&mut unstructured).unwrap_or_default()
20172 }
20173}
20174impl Default for PLAY_TUNE_DATA {
20175 fn default() -> Self {
20176 Self::DEFAULT.clone()
20177 }
20178}
20179impl MessageData for PLAY_TUNE_DATA {
20180 type Message = MavMessage;
20181 const ID: u32 = 258u32;
20182 const NAME: &'static str = "PLAY_TUNE";
20183 const EXTRA_CRC: u8 = 187u8;
20184 const ENCODED_LEN: usize = 232usize;
20185 fn deser(
20186 _version: MavlinkVersion,
20187 __input: &[u8],
20188 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20189 let avail_len = __input.len();
20190 let mut payload_buf = [0; Self::ENCODED_LEN];
20191 let mut buf = if avail_len < Self::ENCODED_LEN {
20192 payload_buf[0..avail_len].copy_from_slice(__input);
20193 Bytes::new(&payload_buf)
20194 } else {
20195 Bytes::new(__input)
20196 };
20197 let mut __struct = Self::default();
20198 __struct.target_system = buf.get_u8();
20199 __struct.target_component = buf.get_u8();
20200 for v in &mut __struct.tune {
20201 let val = buf.get_u8();
20202 *v = val;
20203 }
20204 for v in &mut __struct.tune2 {
20205 let val = buf.get_u8();
20206 *v = val;
20207 }
20208 Ok(__struct)
20209 }
20210 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20211 let mut __tmp = BytesMut::new(bytes);
20212 #[allow(clippy::absurd_extreme_comparisons)]
20213 #[allow(unused_comparisons)]
20214 if __tmp.remaining() < Self::ENCODED_LEN {
20215 panic!(
20216 "buffer is too small (need {} bytes, but got {})",
20217 Self::ENCODED_LEN,
20218 __tmp.remaining(),
20219 )
20220 }
20221 __tmp.put_u8(self.target_system);
20222 __tmp.put_u8(self.target_component);
20223 for val in &self.tune {
20224 __tmp.put_u8(*val);
20225 }
20226 for val in &self.tune2 {
20227 __tmp.put_u8(*val);
20228 }
20229 if matches!(version, MavlinkVersion::V2) {
20230 let len = __tmp.len();
20231 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20232 } else {
20233 __tmp.len()
20234 }
20235 }
20236}
20237#[doc = "id: 114"]
20238#[doc = "Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)."]
20239#[derive(Debug, Clone, PartialEq)]
20240#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20241#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20242pub struct HIL_OPTICAL_FLOW_DATA {
20243 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
20244 pub time_usec: u64,
20245 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
20246 pub integration_time_us: u32,
20247 #[doc = "Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
20248 pub integrated_x: f32,
20249 #[doc = "Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
20250 pub integrated_y: f32,
20251 #[doc = "RH rotation around X axis"]
20252 pub integrated_xgyro: f32,
20253 #[doc = "RH rotation around Y axis"]
20254 pub integrated_ygyro: f32,
20255 #[doc = "RH rotation around Z axis"]
20256 pub integrated_zgyro: f32,
20257 #[doc = "Time since the distance was sampled."]
20258 pub time_delta_distance_us: u32,
20259 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
20260 pub distance: f32,
20261 #[doc = "Temperature"]
20262 pub temperature: i16,
20263 #[doc = "Sensor ID"]
20264 pub sensor_id: u8,
20265 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
20266 pub quality: u8,
20267}
20268impl HIL_OPTICAL_FLOW_DATA {
20269 pub const ENCODED_LEN: usize = 44usize;
20270 pub const DEFAULT: Self = Self {
20271 time_usec: 0_u64,
20272 integration_time_us: 0_u32,
20273 integrated_x: 0.0_f32,
20274 integrated_y: 0.0_f32,
20275 integrated_xgyro: 0.0_f32,
20276 integrated_ygyro: 0.0_f32,
20277 integrated_zgyro: 0.0_f32,
20278 time_delta_distance_us: 0_u32,
20279 distance: 0.0_f32,
20280 temperature: 0_i16,
20281 sensor_id: 0_u8,
20282 quality: 0_u8,
20283 };
20284 #[cfg(feature = "arbitrary")]
20285 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20286 use arbitrary::{Arbitrary, Unstructured};
20287 let mut buf = [0u8; 1024];
20288 rng.fill_bytes(&mut buf);
20289 let mut unstructured = Unstructured::new(&buf);
20290 Self::arbitrary(&mut unstructured).unwrap_or_default()
20291 }
20292}
20293impl Default for HIL_OPTICAL_FLOW_DATA {
20294 fn default() -> Self {
20295 Self::DEFAULT.clone()
20296 }
20297}
20298impl MessageData for HIL_OPTICAL_FLOW_DATA {
20299 type Message = MavMessage;
20300 const ID: u32 = 114u32;
20301 const NAME: &'static str = "HIL_OPTICAL_FLOW";
20302 const EXTRA_CRC: u8 = 237u8;
20303 const ENCODED_LEN: usize = 44usize;
20304 fn deser(
20305 _version: MavlinkVersion,
20306 __input: &[u8],
20307 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20308 let avail_len = __input.len();
20309 let mut payload_buf = [0; Self::ENCODED_LEN];
20310 let mut buf = if avail_len < Self::ENCODED_LEN {
20311 payload_buf[0..avail_len].copy_from_slice(__input);
20312 Bytes::new(&payload_buf)
20313 } else {
20314 Bytes::new(__input)
20315 };
20316 let mut __struct = Self::default();
20317 __struct.time_usec = buf.get_u64_le();
20318 __struct.integration_time_us = buf.get_u32_le();
20319 __struct.integrated_x = buf.get_f32_le();
20320 __struct.integrated_y = buf.get_f32_le();
20321 __struct.integrated_xgyro = buf.get_f32_le();
20322 __struct.integrated_ygyro = buf.get_f32_le();
20323 __struct.integrated_zgyro = buf.get_f32_le();
20324 __struct.time_delta_distance_us = buf.get_u32_le();
20325 __struct.distance = buf.get_f32_le();
20326 __struct.temperature = buf.get_i16_le();
20327 __struct.sensor_id = buf.get_u8();
20328 __struct.quality = buf.get_u8();
20329 Ok(__struct)
20330 }
20331 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20332 let mut __tmp = BytesMut::new(bytes);
20333 #[allow(clippy::absurd_extreme_comparisons)]
20334 #[allow(unused_comparisons)]
20335 if __tmp.remaining() < Self::ENCODED_LEN {
20336 panic!(
20337 "buffer is too small (need {} bytes, but got {})",
20338 Self::ENCODED_LEN,
20339 __tmp.remaining(),
20340 )
20341 }
20342 __tmp.put_u64_le(self.time_usec);
20343 __tmp.put_u32_le(self.integration_time_us);
20344 __tmp.put_f32_le(self.integrated_x);
20345 __tmp.put_f32_le(self.integrated_y);
20346 __tmp.put_f32_le(self.integrated_xgyro);
20347 __tmp.put_f32_le(self.integrated_ygyro);
20348 __tmp.put_f32_le(self.integrated_zgyro);
20349 __tmp.put_u32_le(self.time_delta_distance_us);
20350 __tmp.put_f32_le(self.distance);
20351 __tmp.put_i16_le(self.temperature);
20352 __tmp.put_u8(self.sensor_id);
20353 __tmp.put_u8(self.quality);
20354 if matches!(version, MavlinkVersion::V2) {
20355 let len = __tmp.len();
20356 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20357 } else {
20358 __tmp.len()
20359 }
20360 }
20361}
20362#[doc = "id: 103"]
20363#[doc = "Speed estimate from a vision source."]
20364#[derive(Debug, Clone, PartialEq)]
20365#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20366#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20367pub struct VISION_SPEED_ESTIMATE_DATA {
20368 #[doc = "Timestamp (UNIX time or time since system boot)"]
20369 pub usec: u64,
20370 #[doc = "Global X speed"]
20371 pub x: f32,
20372 #[doc = "Global Y speed"]
20373 pub y: f32,
20374 #[doc = "Global Z speed"]
20375 pub z: f32,
20376 #[doc = "Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array."]
20377 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20378 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20379 pub covariance: [f32; 9],
20380 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
20381 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20382 pub reset_counter: u8,
20383}
20384impl VISION_SPEED_ESTIMATE_DATA {
20385 pub const ENCODED_LEN: usize = 57usize;
20386 pub const DEFAULT: Self = Self {
20387 usec: 0_u64,
20388 x: 0.0_f32,
20389 y: 0.0_f32,
20390 z: 0.0_f32,
20391 covariance: [0.0_f32; 9usize],
20392 reset_counter: 0_u8,
20393 };
20394 #[cfg(feature = "arbitrary")]
20395 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20396 use arbitrary::{Arbitrary, Unstructured};
20397 let mut buf = [0u8; 1024];
20398 rng.fill_bytes(&mut buf);
20399 let mut unstructured = Unstructured::new(&buf);
20400 Self::arbitrary(&mut unstructured).unwrap_or_default()
20401 }
20402}
20403impl Default for VISION_SPEED_ESTIMATE_DATA {
20404 fn default() -> Self {
20405 Self::DEFAULT.clone()
20406 }
20407}
20408impl MessageData for VISION_SPEED_ESTIMATE_DATA {
20409 type Message = MavMessage;
20410 const ID: u32 = 103u32;
20411 const NAME: &'static str = "VISION_SPEED_ESTIMATE";
20412 const EXTRA_CRC: u8 = 208u8;
20413 const ENCODED_LEN: usize = 57usize;
20414 fn deser(
20415 _version: MavlinkVersion,
20416 __input: &[u8],
20417 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20418 let avail_len = __input.len();
20419 let mut payload_buf = [0; Self::ENCODED_LEN];
20420 let mut buf = if avail_len < Self::ENCODED_LEN {
20421 payload_buf[0..avail_len].copy_from_slice(__input);
20422 Bytes::new(&payload_buf)
20423 } else {
20424 Bytes::new(__input)
20425 };
20426 let mut __struct = Self::default();
20427 __struct.usec = buf.get_u64_le();
20428 __struct.x = buf.get_f32_le();
20429 __struct.y = buf.get_f32_le();
20430 __struct.z = buf.get_f32_le();
20431 for v in &mut __struct.covariance {
20432 let val = buf.get_f32_le();
20433 *v = val;
20434 }
20435 __struct.reset_counter = buf.get_u8();
20436 Ok(__struct)
20437 }
20438 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20439 let mut __tmp = BytesMut::new(bytes);
20440 #[allow(clippy::absurd_extreme_comparisons)]
20441 #[allow(unused_comparisons)]
20442 if __tmp.remaining() < Self::ENCODED_LEN {
20443 panic!(
20444 "buffer is too small (need {} bytes, but got {})",
20445 Self::ENCODED_LEN,
20446 __tmp.remaining(),
20447 )
20448 }
20449 __tmp.put_u64_le(self.usec);
20450 __tmp.put_f32_le(self.x);
20451 __tmp.put_f32_le(self.y);
20452 __tmp.put_f32_le(self.z);
20453 for val in &self.covariance {
20454 __tmp.put_f32_le(*val);
20455 }
20456 __tmp.put_u8(self.reset_counter);
20457 if matches!(version, MavlinkVersion::V2) {
20458 let len = __tmp.len();
20459 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20460 } else {
20461 __tmp.len()
20462 }
20463 }
20464}
20465#[doc = "id: 271"]
20466#[doc = "Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
20467#[derive(Debug, Clone, PartialEq)]
20468#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20469#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20470pub struct CAMERA_FOV_STATUS_DATA {
20471 #[doc = "Timestamp (time since system boot)."]
20472 pub time_boot_ms: u32,
20473 #[doc = "Latitude of camera (INT32_MAX if unknown)."]
20474 pub lat_camera: i32,
20475 #[doc = "Longitude of camera (INT32_MAX if unknown)."]
20476 pub lon_camera: i32,
20477 #[doc = "Altitude (MSL) of camera (INT32_MAX if unknown)."]
20478 pub alt_camera: i32,
20479 #[doc = "Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
20480 pub lat_image: i32,
20481 #[doc = "Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
20482 pub lon_image: i32,
20483 #[doc = "Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
20484 pub alt_image: i32,
20485 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
20486 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20487 pub q: [f32; 4],
20488 #[doc = "Horizontal field of view (NaN if unknown)."]
20489 pub hfov: f32,
20490 #[doc = "Vertical field of view (NaN if unknown)."]
20491 pub vfov: f32,
20492 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
20493 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20494 pub camera_device_id: u8,
20495}
20496impl CAMERA_FOV_STATUS_DATA {
20497 pub const ENCODED_LEN: usize = 53usize;
20498 pub const DEFAULT: Self = Self {
20499 time_boot_ms: 0_u32,
20500 lat_camera: 0_i32,
20501 lon_camera: 0_i32,
20502 alt_camera: 0_i32,
20503 lat_image: 0_i32,
20504 lon_image: 0_i32,
20505 alt_image: 0_i32,
20506 q: [0.0_f32; 4usize],
20507 hfov: 0.0_f32,
20508 vfov: 0.0_f32,
20509 camera_device_id: 0_u8,
20510 };
20511 #[cfg(feature = "arbitrary")]
20512 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20513 use arbitrary::{Arbitrary, Unstructured};
20514 let mut buf = [0u8; 1024];
20515 rng.fill_bytes(&mut buf);
20516 let mut unstructured = Unstructured::new(&buf);
20517 Self::arbitrary(&mut unstructured).unwrap_or_default()
20518 }
20519}
20520impl Default for CAMERA_FOV_STATUS_DATA {
20521 fn default() -> Self {
20522 Self::DEFAULT.clone()
20523 }
20524}
20525impl MessageData for CAMERA_FOV_STATUS_DATA {
20526 type Message = MavMessage;
20527 const ID: u32 = 271u32;
20528 const NAME: &'static str = "CAMERA_FOV_STATUS";
20529 const EXTRA_CRC: u8 = 22u8;
20530 const ENCODED_LEN: usize = 53usize;
20531 fn deser(
20532 _version: MavlinkVersion,
20533 __input: &[u8],
20534 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20535 let avail_len = __input.len();
20536 let mut payload_buf = [0; Self::ENCODED_LEN];
20537 let mut buf = if avail_len < Self::ENCODED_LEN {
20538 payload_buf[0..avail_len].copy_from_slice(__input);
20539 Bytes::new(&payload_buf)
20540 } else {
20541 Bytes::new(__input)
20542 };
20543 let mut __struct = Self::default();
20544 __struct.time_boot_ms = buf.get_u32_le();
20545 __struct.lat_camera = buf.get_i32_le();
20546 __struct.lon_camera = buf.get_i32_le();
20547 __struct.alt_camera = buf.get_i32_le();
20548 __struct.lat_image = buf.get_i32_le();
20549 __struct.lon_image = buf.get_i32_le();
20550 __struct.alt_image = buf.get_i32_le();
20551 for v in &mut __struct.q {
20552 let val = buf.get_f32_le();
20553 *v = val;
20554 }
20555 __struct.hfov = buf.get_f32_le();
20556 __struct.vfov = buf.get_f32_le();
20557 __struct.camera_device_id = buf.get_u8();
20558 Ok(__struct)
20559 }
20560 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20561 let mut __tmp = BytesMut::new(bytes);
20562 #[allow(clippy::absurd_extreme_comparisons)]
20563 #[allow(unused_comparisons)]
20564 if __tmp.remaining() < Self::ENCODED_LEN {
20565 panic!(
20566 "buffer is too small (need {} bytes, but got {})",
20567 Self::ENCODED_LEN,
20568 __tmp.remaining(),
20569 )
20570 }
20571 __tmp.put_u32_le(self.time_boot_ms);
20572 __tmp.put_i32_le(self.lat_camera);
20573 __tmp.put_i32_le(self.lon_camera);
20574 __tmp.put_i32_le(self.alt_camera);
20575 __tmp.put_i32_le(self.lat_image);
20576 __tmp.put_i32_le(self.lon_image);
20577 __tmp.put_i32_le(self.alt_image);
20578 for val in &self.q {
20579 __tmp.put_f32_le(*val);
20580 }
20581 __tmp.put_f32_le(self.hfov);
20582 __tmp.put_f32_le(self.vfov);
20583 __tmp.put_u8(self.camera_device_id);
20584 if matches!(version, MavlinkVersion::V2) {
20585 let len = __tmp.len();
20586 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20587 } else {
20588 __tmp.len()
20589 }
20590 }
20591}
20592#[doc = "id: 46"]
20593#[doc = "A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint."]
20594#[derive(Debug, Clone, PartialEq)]
20595#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20596#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20597pub struct MISSION_ITEM_REACHED_DATA {
20598 #[doc = "Sequence"]
20599 pub seq: u16,
20600}
20601impl MISSION_ITEM_REACHED_DATA {
20602 pub const ENCODED_LEN: usize = 2usize;
20603 pub const DEFAULT: Self = Self { seq: 0_u16 };
20604 #[cfg(feature = "arbitrary")]
20605 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20606 use arbitrary::{Arbitrary, Unstructured};
20607 let mut buf = [0u8; 1024];
20608 rng.fill_bytes(&mut buf);
20609 let mut unstructured = Unstructured::new(&buf);
20610 Self::arbitrary(&mut unstructured).unwrap_or_default()
20611 }
20612}
20613impl Default for MISSION_ITEM_REACHED_DATA {
20614 fn default() -> Self {
20615 Self::DEFAULT.clone()
20616 }
20617}
20618impl MessageData for MISSION_ITEM_REACHED_DATA {
20619 type Message = MavMessage;
20620 const ID: u32 = 46u32;
20621 const NAME: &'static str = "MISSION_ITEM_REACHED";
20622 const EXTRA_CRC: u8 = 11u8;
20623 const ENCODED_LEN: usize = 2usize;
20624 fn deser(
20625 _version: MavlinkVersion,
20626 __input: &[u8],
20627 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20628 let avail_len = __input.len();
20629 let mut payload_buf = [0; Self::ENCODED_LEN];
20630 let mut buf = if avail_len < Self::ENCODED_LEN {
20631 payload_buf[0..avail_len].copy_from_slice(__input);
20632 Bytes::new(&payload_buf)
20633 } else {
20634 Bytes::new(__input)
20635 };
20636 let mut __struct = Self::default();
20637 __struct.seq = buf.get_u16_le();
20638 Ok(__struct)
20639 }
20640 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20641 let mut __tmp = BytesMut::new(bytes);
20642 #[allow(clippy::absurd_extreme_comparisons)]
20643 #[allow(unused_comparisons)]
20644 if __tmp.remaining() < Self::ENCODED_LEN {
20645 panic!(
20646 "buffer is too small (need {} bytes, but got {})",
20647 Self::ENCODED_LEN,
20648 __tmp.remaining(),
20649 )
20650 }
20651 __tmp.put_u16_le(self.seq);
20652 if matches!(version, MavlinkVersion::V2) {
20653 let len = __tmp.len();
20654 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20655 } else {
20656 __tmp.len()
20657 }
20658 }
20659}
20660#[doc = "id: 266"]
20661#[doc = "A message containing logged data (see also MAV_CMD_LOGGING_START)."]
20662#[derive(Debug, Clone, PartialEq)]
20663#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20664#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20665pub struct LOGGING_DATA_DATA {
20666 #[doc = "sequence number (can wrap)"]
20667 pub sequence: u16,
20668 #[doc = "system ID of the target"]
20669 pub target_system: u8,
20670 #[doc = "component ID of the target"]
20671 pub target_component: u8,
20672 #[doc = "data length"]
20673 pub length: u8,
20674 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
20675 pub first_message_offset: u8,
20676 #[doc = "logged data"]
20677 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20678 pub data: [u8; 249],
20679}
20680impl LOGGING_DATA_DATA {
20681 pub const ENCODED_LEN: usize = 255usize;
20682 pub const DEFAULT: Self = Self {
20683 sequence: 0_u16,
20684 target_system: 0_u8,
20685 target_component: 0_u8,
20686 length: 0_u8,
20687 first_message_offset: 0_u8,
20688 data: [0_u8; 249usize],
20689 };
20690 #[cfg(feature = "arbitrary")]
20691 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20692 use arbitrary::{Arbitrary, Unstructured};
20693 let mut buf = [0u8; 1024];
20694 rng.fill_bytes(&mut buf);
20695 let mut unstructured = Unstructured::new(&buf);
20696 Self::arbitrary(&mut unstructured).unwrap_or_default()
20697 }
20698}
20699impl Default for LOGGING_DATA_DATA {
20700 fn default() -> Self {
20701 Self::DEFAULT.clone()
20702 }
20703}
20704impl MessageData for LOGGING_DATA_DATA {
20705 type Message = MavMessage;
20706 const ID: u32 = 266u32;
20707 const NAME: &'static str = "LOGGING_DATA";
20708 const EXTRA_CRC: u8 = 193u8;
20709 const ENCODED_LEN: usize = 255usize;
20710 fn deser(
20711 _version: MavlinkVersion,
20712 __input: &[u8],
20713 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20714 let avail_len = __input.len();
20715 let mut payload_buf = [0; Self::ENCODED_LEN];
20716 let mut buf = if avail_len < Self::ENCODED_LEN {
20717 payload_buf[0..avail_len].copy_from_slice(__input);
20718 Bytes::new(&payload_buf)
20719 } else {
20720 Bytes::new(__input)
20721 };
20722 let mut __struct = Self::default();
20723 __struct.sequence = buf.get_u16_le();
20724 __struct.target_system = buf.get_u8();
20725 __struct.target_component = buf.get_u8();
20726 __struct.length = buf.get_u8();
20727 __struct.first_message_offset = buf.get_u8();
20728 for v in &mut __struct.data {
20729 let val = buf.get_u8();
20730 *v = val;
20731 }
20732 Ok(__struct)
20733 }
20734 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20735 let mut __tmp = BytesMut::new(bytes);
20736 #[allow(clippy::absurd_extreme_comparisons)]
20737 #[allow(unused_comparisons)]
20738 if __tmp.remaining() < Self::ENCODED_LEN {
20739 panic!(
20740 "buffer is too small (need {} bytes, but got {})",
20741 Self::ENCODED_LEN,
20742 __tmp.remaining(),
20743 )
20744 }
20745 __tmp.put_u16_le(self.sequence);
20746 __tmp.put_u8(self.target_system);
20747 __tmp.put_u8(self.target_component);
20748 __tmp.put_u8(self.length);
20749 __tmp.put_u8(self.first_message_offset);
20750 for val in &self.data {
20751 __tmp.put_u8(*val);
20752 }
20753 if matches!(version, MavlinkVersion::V2) {
20754 let len = __tmp.len();
20755 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20756 } else {
20757 __tmp.len()
20758 }
20759 }
20760}
20761#[doc = "id: 390"]
20762#[doc = "Hardware status sent by an onboard computer."]
20763#[derive(Debug, Clone, PartialEq)]
20764#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20765#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20766pub struct ONBOARD_COMPUTER_STATUS_DATA {
20767 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
20768 pub time_usec: u64,
20769 #[doc = "Time since system boot."]
20770 pub uptime: u32,
20771 #[doc = "Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused."]
20772 pub ram_usage: u32,
20773 #[doc = "Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused."]
20774 pub ram_total: u32,
20775 #[doc = "Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused."]
20776 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20777 pub storage_type: [u32; 4],
20778 #[doc = "Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused."]
20779 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20780 pub storage_usage: [u32; 4],
20781 #[doc = "Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused."]
20782 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20783 pub storage_total: [u32; 4],
20784 #[doc = "Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary"]
20785 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20786 pub link_type: [u32; 6],
20787 #[doc = "Network traffic from the component system. A value of UINT32_MAX implies the field is unused."]
20788 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20789 pub link_tx_rate: [u32; 6],
20790 #[doc = "Network traffic to the component system. A value of UINT32_MAX implies the field is unused."]
20791 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20792 pub link_rx_rate: [u32; 6],
20793 #[doc = "Network capacity from the component system. A value of UINT32_MAX implies the field is unused."]
20794 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20795 pub link_tx_max: [u32; 6],
20796 #[doc = "Network capacity to the component system. A value of UINT32_MAX implies the field is unused."]
20797 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20798 pub link_rx_max: [u32; 6],
20799 #[doc = "Fan speeds. A value of INT16_MAX implies the field is unused."]
20800 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20801 pub fan_speed: [i16; 4],
20802 #[doc = "Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers."]
20803 pub mavtype: u8,
20804 #[doc = "CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
20805 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20806 pub cpu_cores: [u8; 8],
20807 #[doc = "Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
20808 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20809 pub cpu_combined: [u8; 10],
20810 #[doc = "GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
20811 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20812 pub gpu_cores: [u8; 4],
20813 #[doc = "Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
20814 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20815 pub gpu_combined: [u8; 10],
20816 #[doc = "Temperature of the board. A value of INT8_MAX implies the field is unused."]
20817 pub temperature_board: i8,
20818 #[doc = "Temperature of the CPU core. A value of INT8_MAX implies the field is unused."]
20819 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20820 pub temperature_core: [i8; 8],
20821}
20822impl ONBOARD_COMPUTER_STATUS_DATA {
20823 pub const ENCODED_LEN: usize = 238usize;
20824 pub const DEFAULT: Self = Self {
20825 time_usec: 0_u64,
20826 uptime: 0_u32,
20827 ram_usage: 0_u32,
20828 ram_total: 0_u32,
20829 storage_type: [0_u32; 4usize],
20830 storage_usage: [0_u32; 4usize],
20831 storage_total: [0_u32; 4usize],
20832 link_type: [0_u32; 6usize],
20833 link_tx_rate: [0_u32; 6usize],
20834 link_rx_rate: [0_u32; 6usize],
20835 link_tx_max: [0_u32; 6usize],
20836 link_rx_max: [0_u32; 6usize],
20837 fan_speed: [0_i16; 4usize],
20838 mavtype: 0_u8,
20839 cpu_cores: [0_u8; 8usize],
20840 cpu_combined: [0_u8; 10usize],
20841 gpu_cores: [0_u8; 4usize],
20842 gpu_combined: [0_u8; 10usize],
20843 temperature_board: 0_i8,
20844 temperature_core: [0_i8; 8usize],
20845 };
20846 #[cfg(feature = "arbitrary")]
20847 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20848 use arbitrary::{Arbitrary, Unstructured};
20849 let mut buf = [0u8; 1024];
20850 rng.fill_bytes(&mut buf);
20851 let mut unstructured = Unstructured::new(&buf);
20852 Self::arbitrary(&mut unstructured).unwrap_or_default()
20853 }
20854}
20855impl Default for ONBOARD_COMPUTER_STATUS_DATA {
20856 fn default() -> Self {
20857 Self::DEFAULT.clone()
20858 }
20859}
20860impl MessageData for ONBOARD_COMPUTER_STATUS_DATA {
20861 type Message = MavMessage;
20862 const ID: u32 = 390u32;
20863 const NAME: &'static str = "ONBOARD_COMPUTER_STATUS";
20864 const EXTRA_CRC: u8 = 156u8;
20865 const ENCODED_LEN: usize = 238usize;
20866 fn deser(
20867 _version: MavlinkVersion,
20868 __input: &[u8],
20869 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20870 let avail_len = __input.len();
20871 let mut payload_buf = [0; Self::ENCODED_LEN];
20872 let mut buf = if avail_len < Self::ENCODED_LEN {
20873 payload_buf[0..avail_len].copy_from_slice(__input);
20874 Bytes::new(&payload_buf)
20875 } else {
20876 Bytes::new(__input)
20877 };
20878 let mut __struct = Self::default();
20879 __struct.time_usec = buf.get_u64_le();
20880 __struct.uptime = buf.get_u32_le();
20881 __struct.ram_usage = buf.get_u32_le();
20882 __struct.ram_total = buf.get_u32_le();
20883 for v in &mut __struct.storage_type {
20884 let val = buf.get_u32_le();
20885 *v = val;
20886 }
20887 for v in &mut __struct.storage_usage {
20888 let val = buf.get_u32_le();
20889 *v = val;
20890 }
20891 for v in &mut __struct.storage_total {
20892 let val = buf.get_u32_le();
20893 *v = val;
20894 }
20895 for v in &mut __struct.link_type {
20896 let val = buf.get_u32_le();
20897 *v = val;
20898 }
20899 for v in &mut __struct.link_tx_rate {
20900 let val = buf.get_u32_le();
20901 *v = val;
20902 }
20903 for v in &mut __struct.link_rx_rate {
20904 let val = buf.get_u32_le();
20905 *v = val;
20906 }
20907 for v in &mut __struct.link_tx_max {
20908 let val = buf.get_u32_le();
20909 *v = val;
20910 }
20911 for v in &mut __struct.link_rx_max {
20912 let val = buf.get_u32_le();
20913 *v = val;
20914 }
20915 for v in &mut __struct.fan_speed {
20916 let val = buf.get_i16_le();
20917 *v = val;
20918 }
20919 __struct.mavtype = buf.get_u8();
20920 for v in &mut __struct.cpu_cores {
20921 let val = buf.get_u8();
20922 *v = val;
20923 }
20924 for v in &mut __struct.cpu_combined {
20925 let val = buf.get_u8();
20926 *v = val;
20927 }
20928 for v in &mut __struct.gpu_cores {
20929 let val = buf.get_u8();
20930 *v = val;
20931 }
20932 for v in &mut __struct.gpu_combined {
20933 let val = buf.get_u8();
20934 *v = val;
20935 }
20936 __struct.temperature_board = buf.get_i8();
20937 for v in &mut __struct.temperature_core {
20938 let val = buf.get_i8();
20939 *v = val;
20940 }
20941 Ok(__struct)
20942 }
20943 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20944 let mut __tmp = BytesMut::new(bytes);
20945 #[allow(clippy::absurd_extreme_comparisons)]
20946 #[allow(unused_comparisons)]
20947 if __tmp.remaining() < Self::ENCODED_LEN {
20948 panic!(
20949 "buffer is too small (need {} bytes, but got {})",
20950 Self::ENCODED_LEN,
20951 __tmp.remaining(),
20952 )
20953 }
20954 __tmp.put_u64_le(self.time_usec);
20955 __tmp.put_u32_le(self.uptime);
20956 __tmp.put_u32_le(self.ram_usage);
20957 __tmp.put_u32_le(self.ram_total);
20958 for val in &self.storage_type {
20959 __tmp.put_u32_le(*val);
20960 }
20961 for val in &self.storage_usage {
20962 __tmp.put_u32_le(*val);
20963 }
20964 for val in &self.storage_total {
20965 __tmp.put_u32_le(*val);
20966 }
20967 for val in &self.link_type {
20968 __tmp.put_u32_le(*val);
20969 }
20970 for val in &self.link_tx_rate {
20971 __tmp.put_u32_le(*val);
20972 }
20973 for val in &self.link_rx_rate {
20974 __tmp.put_u32_le(*val);
20975 }
20976 for val in &self.link_tx_max {
20977 __tmp.put_u32_le(*val);
20978 }
20979 for val in &self.link_rx_max {
20980 __tmp.put_u32_le(*val);
20981 }
20982 for val in &self.fan_speed {
20983 __tmp.put_i16_le(*val);
20984 }
20985 __tmp.put_u8(self.mavtype);
20986 for val in &self.cpu_cores {
20987 __tmp.put_u8(*val);
20988 }
20989 for val in &self.cpu_combined {
20990 __tmp.put_u8(*val);
20991 }
20992 for val in &self.gpu_cores {
20993 __tmp.put_u8(*val);
20994 }
20995 for val in &self.gpu_combined {
20996 __tmp.put_u8(*val);
20997 }
20998 __tmp.put_i8(self.temperature_board);
20999 for val in &self.temperature_core {
21000 __tmp.put_i8(*val);
21001 }
21002 if matches!(version, MavlinkVersion::V2) {
21003 let len = __tmp.len();
21004 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21005 } else {
21006 __tmp.len()
21007 }
21008 }
21009}
21010#[doc = "id: 121"]
21011#[doc = "Erase all logs."]
21012#[derive(Debug, Clone, PartialEq)]
21013#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21014#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21015pub struct LOG_ERASE_DATA {
21016 #[doc = "System ID"]
21017 pub target_system: u8,
21018 #[doc = "Component ID"]
21019 pub target_component: u8,
21020}
21021impl LOG_ERASE_DATA {
21022 pub const ENCODED_LEN: usize = 2usize;
21023 pub const DEFAULT: Self = Self {
21024 target_system: 0_u8,
21025 target_component: 0_u8,
21026 };
21027 #[cfg(feature = "arbitrary")]
21028 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21029 use arbitrary::{Arbitrary, Unstructured};
21030 let mut buf = [0u8; 1024];
21031 rng.fill_bytes(&mut buf);
21032 let mut unstructured = Unstructured::new(&buf);
21033 Self::arbitrary(&mut unstructured).unwrap_or_default()
21034 }
21035}
21036impl Default for LOG_ERASE_DATA {
21037 fn default() -> Self {
21038 Self::DEFAULT.clone()
21039 }
21040}
21041impl MessageData for LOG_ERASE_DATA {
21042 type Message = MavMessage;
21043 const ID: u32 = 121u32;
21044 const NAME: &'static str = "LOG_ERASE";
21045 const EXTRA_CRC: u8 = 237u8;
21046 const ENCODED_LEN: usize = 2usize;
21047 fn deser(
21048 _version: MavlinkVersion,
21049 __input: &[u8],
21050 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21051 let avail_len = __input.len();
21052 let mut payload_buf = [0; Self::ENCODED_LEN];
21053 let mut buf = if avail_len < Self::ENCODED_LEN {
21054 payload_buf[0..avail_len].copy_from_slice(__input);
21055 Bytes::new(&payload_buf)
21056 } else {
21057 Bytes::new(__input)
21058 };
21059 let mut __struct = Self::default();
21060 __struct.target_system = buf.get_u8();
21061 __struct.target_component = buf.get_u8();
21062 Ok(__struct)
21063 }
21064 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21065 let mut __tmp = BytesMut::new(bytes);
21066 #[allow(clippy::absurd_extreme_comparisons)]
21067 #[allow(unused_comparisons)]
21068 if __tmp.remaining() < Self::ENCODED_LEN {
21069 panic!(
21070 "buffer is too small (need {} bytes, but got {})",
21071 Self::ENCODED_LEN,
21072 __tmp.remaining(),
21073 )
21074 }
21075 __tmp.put_u8(self.target_system);
21076 __tmp.put_u8(self.target_component);
21077 if matches!(version, MavlinkVersion::V2) {
21078 let len = __tmp.len();
21079 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21080 } else {
21081 __tmp.len()
21082 }
21083 }
21084}
21085#[doc = "id: 9000"]
21086#[doc = "Cumulative distance traveled for each reported wheel."]
21087#[derive(Debug, Clone, PartialEq)]
21088#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21089#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21090pub struct WHEEL_DISTANCE_DATA {
21091 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
21092 pub time_usec: u64,
21093 #[doc = "Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints."]
21094 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21095 pub distance: [f64; 16],
21096 #[doc = "Number of wheels reported."]
21097 pub count: u8,
21098}
21099impl WHEEL_DISTANCE_DATA {
21100 pub const ENCODED_LEN: usize = 137usize;
21101 pub const DEFAULT: Self = Self {
21102 time_usec: 0_u64,
21103 distance: [0.0_f64; 16usize],
21104 count: 0_u8,
21105 };
21106 #[cfg(feature = "arbitrary")]
21107 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21108 use arbitrary::{Arbitrary, Unstructured};
21109 let mut buf = [0u8; 1024];
21110 rng.fill_bytes(&mut buf);
21111 let mut unstructured = Unstructured::new(&buf);
21112 Self::arbitrary(&mut unstructured).unwrap_or_default()
21113 }
21114}
21115impl Default for WHEEL_DISTANCE_DATA {
21116 fn default() -> Self {
21117 Self::DEFAULT.clone()
21118 }
21119}
21120impl MessageData for WHEEL_DISTANCE_DATA {
21121 type Message = MavMessage;
21122 const ID: u32 = 9000u32;
21123 const NAME: &'static str = "WHEEL_DISTANCE";
21124 const EXTRA_CRC: u8 = 113u8;
21125 const ENCODED_LEN: usize = 137usize;
21126 fn deser(
21127 _version: MavlinkVersion,
21128 __input: &[u8],
21129 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21130 let avail_len = __input.len();
21131 let mut payload_buf = [0; Self::ENCODED_LEN];
21132 let mut buf = if avail_len < Self::ENCODED_LEN {
21133 payload_buf[0..avail_len].copy_from_slice(__input);
21134 Bytes::new(&payload_buf)
21135 } else {
21136 Bytes::new(__input)
21137 };
21138 let mut __struct = Self::default();
21139 __struct.time_usec = buf.get_u64_le();
21140 for v in &mut __struct.distance {
21141 let val = buf.get_f64_le();
21142 *v = val;
21143 }
21144 __struct.count = buf.get_u8();
21145 Ok(__struct)
21146 }
21147 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21148 let mut __tmp = BytesMut::new(bytes);
21149 #[allow(clippy::absurd_extreme_comparisons)]
21150 #[allow(unused_comparisons)]
21151 if __tmp.remaining() < Self::ENCODED_LEN {
21152 panic!(
21153 "buffer is too small (need {} bytes, but got {})",
21154 Self::ENCODED_LEN,
21155 __tmp.remaining(),
21156 )
21157 }
21158 __tmp.put_u64_le(self.time_usec);
21159 for val in &self.distance {
21160 __tmp.put_f64_le(*val);
21161 }
21162 __tmp.put_u8(self.count);
21163 if matches!(version, MavlinkVersion::V2) {
21164 let len = __tmp.len();
21165 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21166 } else {
21167 __tmp.len()
21168 }
21169 }
21170}
21171#[doc = "id: 322"]
21172#[doc = "Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout."]
21173#[derive(Debug, Clone, PartialEq)]
21174#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21175#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21176pub struct PARAM_EXT_VALUE_DATA {
21177 #[doc = "Total number of parameters"]
21178 pub param_count: u16,
21179 #[doc = "Index of this parameter"]
21180 pub param_index: u16,
21181 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
21182 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21183 pub param_id: [u8; 16],
21184 #[doc = "Parameter value"]
21185 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21186 pub param_value: [u8; 128],
21187 #[doc = "Parameter type."]
21188 pub param_type: MavParamExtType,
21189}
21190impl PARAM_EXT_VALUE_DATA {
21191 pub const ENCODED_LEN: usize = 149usize;
21192 pub const DEFAULT: Self = Self {
21193 param_count: 0_u16,
21194 param_index: 0_u16,
21195 param_id: [0_u8; 16usize],
21196 param_value: [0_u8; 128usize],
21197 param_type: MavParamExtType::DEFAULT,
21198 };
21199 #[cfg(feature = "arbitrary")]
21200 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21201 use arbitrary::{Arbitrary, Unstructured};
21202 let mut buf = [0u8; 1024];
21203 rng.fill_bytes(&mut buf);
21204 let mut unstructured = Unstructured::new(&buf);
21205 Self::arbitrary(&mut unstructured).unwrap_or_default()
21206 }
21207}
21208impl Default for PARAM_EXT_VALUE_DATA {
21209 fn default() -> Self {
21210 Self::DEFAULT.clone()
21211 }
21212}
21213impl MessageData for PARAM_EXT_VALUE_DATA {
21214 type Message = MavMessage;
21215 const ID: u32 = 322u32;
21216 const NAME: &'static str = "PARAM_EXT_VALUE";
21217 const EXTRA_CRC: u8 = 243u8;
21218 const ENCODED_LEN: usize = 149usize;
21219 fn deser(
21220 _version: MavlinkVersion,
21221 __input: &[u8],
21222 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21223 let avail_len = __input.len();
21224 let mut payload_buf = [0; Self::ENCODED_LEN];
21225 let mut buf = if avail_len < Self::ENCODED_LEN {
21226 payload_buf[0..avail_len].copy_from_slice(__input);
21227 Bytes::new(&payload_buf)
21228 } else {
21229 Bytes::new(__input)
21230 };
21231 let mut __struct = Self::default();
21232 __struct.param_count = buf.get_u16_le();
21233 __struct.param_index = buf.get_u16_le();
21234 for v in &mut __struct.param_id {
21235 let val = buf.get_u8();
21236 *v = val;
21237 }
21238 for v in &mut __struct.param_value {
21239 let val = buf.get_u8();
21240 *v = val;
21241 }
21242 let tmp = buf.get_u8();
21243 __struct.param_type =
21244 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21245 enum_type: "MavParamExtType",
21246 value: tmp as u32,
21247 })?;
21248 Ok(__struct)
21249 }
21250 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21251 let mut __tmp = BytesMut::new(bytes);
21252 #[allow(clippy::absurd_extreme_comparisons)]
21253 #[allow(unused_comparisons)]
21254 if __tmp.remaining() < Self::ENCODED_LEN {
21255 panic!(
21256 "buffer is too small (need {} bytes, but got {})",
21257 Self::ENCODED_LEN,
21258 __tmp.remaining(),
21259 )
21260 }
21261 __tmp.put_u16_le(self.param_count);
21262 __tmp.put_u16_le(self.param_index);
21263 for val in &self.param_id {
21264 __tmp.put_u8(*val);
21265 }
21266 for val in &self.param_value {
21267 __tmp.put_u8(*val);
21268 }
21269 __tmp.put_u8(self.param_type as u8);
21270 if matches!(version, MavlinkVersion::V2) {
21271 let len = __tmp.len();
21272 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21273 } else {
21274 __tmp.len()
21275 }
21276 }
21277}
21278#[doc = "id: 34"]
21279#[doc = "The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to INT16_MAX."]
21280#[derive(Debug, Clone, PartialEq)]
21281#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21282#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21283pub struct RC_CHANNELS_SCALED_DATA {
21284 #[doc = "Timestamp (time since system boot)."]
21285 pub time_boot_ms: u32,
21286 #[doc = "RC channel 1 value scaled."]
21287 pub chan1_scaled: i16,
21288 #[doc = "RC channel 2 value scaled."]
21289 pub chan2_scaled: i16,
21290 #[doc = "RC channel 3 value scaled."]
21291 pub chan3_scaled: i16,
21292 #[doc = "RC channel 4 value scaled."]
21293 pub chan4_scaled: i16,
21294 #[doc = "RC channel 5 value scaled."]
21295 pub chan5_scaled: i16,
21296 #[doc = "RC channel 6 value scaled."]
21297 pub chan6_scaled: i16,
21298 #[doc = "RC channel 7 value scaled."]
21299 pub chan7_scaled: i16,
21300 #[doc = "RC channel 8 value scaled."]
21301 pub chan8_scaled: i16,
21302 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
21303 pub port: u8,
21304 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
21305 pub rssi: u8,
21306}
21307impl RC_CHANNELS_SCALED_DATA {
21308 pub const ENCODED_LEN: usize = 22usize;
21309 pub const DEFAULT: Self = Self {
21310 time_boot_ms: 0_u32,
21311 chan1_scaled: 0_i16,
21312 chan2_scaled: 0_i16,
21313 chan3_scaled: 0_i16,
21314 chan4_scaled: 0_i16,
21315 chan5_scaled: 0_i16,
21316 chan6_scaled: 0_i16,
21317 chan7_scaled: 0_i16,
21318 chan8_scaled: 0_i16,
21319 port: 0_u8,
21320 rssi: 0_u8,
21321 };
21322 #[cfg(feature = "arbitrary")]
21323 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21324 use arbitrary::{Arbitrary, Unstructured};
21325 let mut buf = [0u8; 1024];
21326 rng.fill_bytes(&mut buf);
21327 let mut unstructured = Unstructured::new(&buf);
21328 Self::arbitrary(&mut unstructured).unwrap_or_default()
21329 }
21330}
21331impl Default for RC_CHANNELS_SCALED_DATA {
21332 fn default() -> Self {
21333 Self::DEFAULT.clone()
21334 }
21335}
21336impl MessageData for RC_CHANNELS_SCALED_DATA {
21337 type Message = MavMessage;
21338 const ID: u32 = 34u32;
21339 const NAME: &'static str = "RC_CHANNELS_SCALED";
21340 const EXTRA_CRC: u8 = 237u8;
21341 const ENCODED_LEN: usize = 22usize;
21342 fn deser(
21343 _version: MavlinkVersion,
21344 __input: &[u8],
21345 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21346 let avail_len = __input.len();
21347 let mut payload_buf = [0; Self::ENCODED_LEN];
21348 let mut buf = if avail_len < Self::ENCODED_LEN {
21349 payload_buf[0..avail_len].copy_from_slice(__input);
21350 Bytes::new(&payload_buf)
21351 } else {
21352 Bytes::new(__input)
21353 };
21354 let mut __struct = Self::default();
21355 __struct.time_boot_ms = buf.get_u32_le();
21356 __struct.chan1_scaled = buf.get_i16_le();
21357 __struct.chan2_scaled = buf.get_i16_le();
21358 __struct.chan3_scaled = buf.get_i16_le();
21359 __struct.chan4_scaled = buf.get_i16_le();
21360 __struct.chan5_scaled = buf.get_i16_le();
21361 __struct.chan6_scaled = buf.get_i16_le();
21362 __struct.chan7_scaled = buf.get_i16_le();
21363 __struct.chan8_scaled = buf.get_i16_le();
21364 __struct.port = buf.get_u8();
21365 __struct.rssi = buf.get_u8();
21366 Ok(__struct)
21367 }
21368 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21369 let mut __tmp = BytesMut::new(bytes);
21370 #[allow(clippy::absurd_extreme_comparisons)]
21371 #[allow(unused_comparisons)]
21372 if __tmp.remaining() < Self::ENCODED_LEN {
21373 panic!(
21374 "buffer is too small (need {} bytes, but got {})",
21375 Self::ENCODED_LEN,
21376 __tmp.remaining(),
21377 )
21378 }
21379 __tmp.put_u32_le(self.time_boot_ms);
21380 __tmp.put_i16_le(self.chan1_scaled);
21381 __tmp.put_i16_le(self.chan2_scaled);
21382 __tmp.put_i16_le(self.chan3_scaled);
21383 __tmp.put_i16_le(self.chan4_scaled);
21384 __tmp.put_i16_le(self.chan5_scaled);
21385 __tmp.put_i16_le(self.chan6_scaled);
21386 __tmp.put_i16_le(self.chan7_scaled);
21387 __tmp.put_i16_le(self.chan8_scaled);
21388 __tmp.put_u8(self.port);
21389 __tmp.put_u8(self.rssi);
21390 if matches!(version, MavlinkVersion::V2) {
21391 let len = __tmp.len();
21392 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21393 } else {
21394 __tmp.len()
21395 }
21396 }
21397}
21398#[doc = "id: 83"]
21399#[doc = "Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way."]
21400#[derive(Debug, Clone, PartialEq)]
21401#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21402#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21403pub struct ATTITUDE_TARGET_DATA {
21404 #[doc = "Timestamp (time since system boot)."]
21405 pub time_boot_ms: u32,
21406 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
21407 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21408 pub q: [f32; 4],
21409 #[doc = "Body roll rate"]
21410 pub body_roll_rate: f32,
21411 #[doc = "Body pitch rate"]
21412 pub body_pitch_rate: f32,
21413 #[doc = "Body yaw rate"]
21414 pub body_yaw_rate: f32,
21415 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
21416 pub thrust: f32,
21417 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
21418 pub type_mask: AttitudeTargetTypemask,
21419}
21420impl ATTITUDE_TARGET_DATA {
21421 pub const ENCODED_LEN: usize = 37usize;
21422 pub const DEFAULT: Self = Self {
21423 time_boot_ms: 0_u32,
21424 q: [0.0_f32; 4usize],
21425 body_roll_rate: 0.0_f32,
21426 body_pitch_rate: 0.0_f32,
21427 body_yaw_rate: 0.0_f32,
21428 thrust: 0.0_f32,
21429 type_mask: AttitudeTargetTypemask::DEFAULT,
21430 };
21431 #[cfg(feature = "arbitrary")]
21432 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21433 use arbitrary::{Arbitrary, Unstructured};
21434 let mut buf = [0u8; 1024];
21435 rng.fill_bytes(&mut buf);
21436 let mut unstructured = Unstructured::new(&buf);
21437 Self::arbitrary(&mut unstructured).unwrap_or_default()
21438 }
21439}
21440impl Default for ATTITUDE_TARGET_DATA {
21441 fn default() -> Self {
21442 Self::DEFAULT.clone()
21443 }
21444}
21445impl MessageData for ATTITUDE_TARGET_DATA {
21446 type Message = MavMessage;
21447 const ID: u32 = 83u32;
21448 const NAME: &'static str = "ATTITUDE_TARGET";
21449 const EXTRA_CRC: u8 = 22u8;
21450 const ENCODED_LEN: usize = 37usize;
21451 fn deser(
21452 _version: MavlinkVersion,
21453 __input: &[u8],
21454 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21455 let avail_len = __input.len();
21456 let mut payload_buf = [0; Self::ENCODED_LEN];
21457 let mut buf = if avail_len < Self::ENCODED_LEN {
21458 payload_buf[0..avail_len].copy_from_slice(__input);
21459 Bytes::new(&payload_buf)
21460 } else {
21461 Bytes::new(__input)
21462 };
21463 let mut __struct = Self::default();
21464 __struct.time_boot_ms = buf.get_u32_le();
21465 for v in &mut __struct.q {
21466 let val = buf.get_f32_le();
21467 *v = val;
21468 }
21469 __struct.body_roll_rate = buf.get_f32_le();
21470 __struct.body_pitch_rate = buf.get_f32_le();
21471 __struct.body_yaw_rate = buf.get_f32_le();
21472 __struct.thrust = buf.get_f32_le();
21473 let tmp = buf.get_u8();
21474 __struct.type_mask = AttitudeTargetTypemask::from_bits(
21475 tmp & AttitudeTargetTypemask::all().bits(),
21476 )
21477 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
21478 flag_type: "AttitudeTargetTypemask",
21479 value: tmp as u32,
21480 })?;
21481 Ok(__struct)
21482 }
21483 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21484 let mut __tmp = BytesMut::new(bytes);
21485 #[allow(clippy::absurd_extreme_comparisons)]
21486 #[allow(unused_comparisons)]
21487 if __tmp.remaining() < Self::ENCODED_LEN {
21488 panic!(
21489 "buffer is too small (need {} bytes, but got {})",
21490 Self::ENCODED_LEN,
21491 __tmp.remaining(),
21492 )
21493 }
21494 __tmp.put_u32_le(self.time_boot_ms);
21495 for val in &self.q {
21496 __tmp.put_f32_le(*val);
21497 }
21498 __tmp.put_f32_le(self.body_roll_rate);
21499 __tmp.put_f32_le(self.body_pitch_rate);
21500 __tmp.put_f32_le(self.body_yaw_rate);
21501 __tmp.put_f32_le(self.thrust);
21502 __tmp.put_u8(self.type_mask.bits());
21503 if matches!(version, MavlinkVersion::V2) {
21504 let len = __tmp.len();
21505 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21506 } else {
21507 __tmp.len()
21508 }
21509 }
21510}
21511#[doc = "id: 31"]
21512#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
21513#[derive(Debug, Clone, PartialEq)]
21514#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21515#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21516pub struct ATTITUDE_QUATERNION_DATA {
21517 #[doc = "Timestamp (time since system boot)."]
21518 pub time_boot_ms: u32,
21519 #[doc = "Quaternion component 1, w (1 in null-rotation)"]
21520 pub q1: f32,
21521 #[doc = "Quaternion component 2, x (0 in null-rotation)"]
21522 pub q2: f32,
21523 #[doc = "Quaternion component 3, y (0 in null-rotation)"]
21524 pub q3: f32,
21525 #[doc = "Quaternion component 4, z (0 in null-rotation)"]
21526 pub q4: f32,
21527 #[doc = "Roll angular speed"]
21528 pub rollspeed: f32,
21529 #[doc = "Pitch angular speed"]
21530 pub pitchspeed: f32,
21531 #[doc = "Yaw angular speed"]
21532 pub yawspeed: f32,
21533 #[doc = "Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode."]
21534 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21535 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21536 pub repr_offset_q: [f32; 4],
21537}
21538impl ATTITUDE_QUATERNION_DATA {
21539 pub const ENCODED_LEN: usize = 48usize;
21540 pub const DEFAULT: Self = Self {
21541 time_boot_ms: 0_u32,
21542 q1: 0.0_f32,
21543 q2: 0.0_f32,
21544 q3: 0.0_f32,
21545 q4: 0.0_f32,
21546 rollspeed: 0.0_f32,
21547 pitchspeed: 0.0_f32,
21548 yawspeed: 0.0_f32,
21549 repr_offset_q: [0.0_f32; 4usize],
21550 };
21551 #[cfg(feature = "arbitrary")]
21552 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21553 use arbitrary::{Arbitrary, Unstructured};
21554 let mut buf = [0u8; 1024];
21555 rng.fill_bytes(&mut buf);
21556 let mut unstructured = Unstructured::new(&buf);
21557 Self::arbitrary(&mut unstructured).unwrap_or_default()
21558 }
21559}
21560impl Default for ATTITUDE_QUATERNION_DATA {
21561 fn default() -> Self {
21562 Self::DEFAULT.clone()
21563 }
21564}
21565impl MessageData for ATTITUDE_QUATERNION_DATA {
21566 type Message = MavMessage;
21567 const ID: u32 = 31u32;
21568 const NAME: &'static str = "ATTITUDE_QUATERNION";
21569 const EXTRA_CRC: u8 = 246u8;
21570 const ENCODED_LEN: usize = 48usize;
21571 fn deser(
21572 _version: MavlinkVersion,
21573 __input: &[u8],
21574 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21575 let avail_len = __input.len();
21576 let mut payload_buf = [0; Self::ENCODED_LEN];
21577 let mut buf = if avail_len < Self::ENCODED_LEN {
21578 payload_buf[0..avail_len].copy_from_slice(__input);
21579 Bytes::new(&payload_buf)
21580 } else {
21581 Bytes::new(__input)
21582 };
21583 let mut __struct = Self::default();
21584 __struct.time_boot_ms = buf.get_u32_le();
21585 __struct.q1 = buf.get_f32_le();
21586 __struct.q2 = buf.get_f32_le();
21587 __struct.q3 = buf.get_f32_le();
21588 __struct.q4 = buf.get_f32_le();
21589 __struct.rollspeed = buf.get_f32_le();
21590 __struct.pitchspeed = buf.get_f32_le();
21591 __struct.yawspeed = buf.get_f32_le();
21592 for v in &mut __struct.repr_offset_q {
21593 let val = buf.get_f32_le();
21594 *v = val;
21595 }
21596 Ok(__struct)
21597 }
21598 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21599 let mut __tmp = BytesMut::new(bytes);
21600 #[allow(clippy::absurd_extreme_comparisons)]
21601 #[allow(unused_comparisons)]
21602 if __tmp.remaining() < Self::ENCODED_LEN {
21603 panic!(
21604 "buffer is too small (need {} bytes, but got {})",
21605 Self::ENCODED_LEN,
21606 __tmp.remaining(),
21607 )
21608 }
21609 __tmp.put_u32_le(self.time_boot_ms);
21610 __tmp.put_f32_le(self.q1);
21611 __tmp.put_f32_le(self.q2);
21612 __tmp.put_f32_le(self.q3);
21613 __tmp.put_f32_le(self.q4);
21614 __tmp.put_f32_le(self.rollspeed);
21615 __tmp.put_f32_le(self.pitchspeed);
21616 __tmp.put_f32_le(self.yawspeed);
21617 for val in &self.repr_offset_q {
21618 __tmp.put_f32_le(*val);
21619 }
21620 if matches!(version, MavlinkVersion::V2) {
21621 let len = __tmp.len();
21622 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21623 } else {
21624 __tmp.len()
21625 }
21626 }
21627}
21628#[doc = "id: 90"]
21629#[doc = "Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations."]
21630#[derive(Debug, Clone, PartialEq)]
21631#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21632#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21633pub struct HIL_STATE_DATA {
21634 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
21635 pub time_usec: u64,
21636 #[doc = "Roll angle"]
21637 pub roll: f32,
21638 #[doc = "Pitch angle"]
21639 pub pitch: f32,
21640 #[doc = "Yaw angle"]
21641 pub yaw: f32,
21642 #[doc = "Body frame roll / phi angular speed"]
21643 pub rollspeed: f32,
21644 #[doc = "Body frame pitch / theta angular speed"]
21645 pub pitchspeed: f32,
21646 #[doc = "Body frame yaw / psi angular speed"]
21647 pub yawspeed: f32,
21648 #[doc = "Latitude"]
21649 pub lat: i32,
21650 #[doc = "Longitude"]
21651 pub lon: i32,
21652 #[doc = "Altitude"]
21653 pub alt: i32,
21654 #[doc = "Ground X Speed (Latitude)"]
21655 pub vx: i16,
21656 #[doc = "Ground Y Speed (Longitude)"]
21657 pub vy: i16,
21658 #[doc = "Ground Z Speed (Altitude)"]
21659 pub vz: i16,
21660 #[doc = "X acceleration"]
21661 pub xacc: i16,
21662 #[doc = "Y acceleration"]
21663 pub yacc: i16,
21664 #[doc = "Z acceleration"]
21665 pub zacc: i16,
21666}
21667impl HIL_STATE_DATA {
21668 pub const ENCODED_LEN: usize = 56usize;
21669 pub const DEFAULT: Self = Self {
21670 time_usec: 0_u64,
21671 roll: 0.0_f32,
21672 pitch: 0.0_f32,
21673 yaw: 0.0_f32,
21674 rollspeed: 0.0_f32,
21675 pitchspeed: 0.0_f32,
21676 yawspeed: 0.0_f32,
21677 lat: 0_i32,
21678 lon: 0_i32,
21679 alt: 0_i32,
21680 vx: 0_i16,
21681 vy: 0_i16,
21682 vz: 0_i16,
21683 xacc: 0_i16,
21684 yacc: 0_i16,
21685 zacc: 0_i16,
21686 };
21687 #[cfg(feature = "arbitrary")]
21688 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21689 use arbitrary::{Arbitrary, Unstructured};
21690 let mut buf = [0u8; 1024];
21691 rng.fill_bytes(&mut buf);
21692 let mut unstructured = Unstructured::new(&buf);
21693 Self::arbitrary(&mut unstructured).unwrap_or_default()
21694 }
21695}
21696impl Default for HIL_STATE_DATA {
21697 fn default() -> Self {
21698 Self::DEFAULT.clone()
21699 }
21700}
21701impl MessageData for HIL_STATE_DATA {
21702 type Message = MavMessage;
21703 const ID: u32 = 90u32;
21704 const NAME: &'static str = "HIL_STATE";
21705 const EXTRA_CRC: u8 = 183u8;
21706 const ENCODED_LEN: usize = 56usize;
21707 fn deser(
21708 _version: MavlinkVersion,
21709 __input: &[u8],
21710 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21711 let avail_len = __input.len();
21712 let mut payload_buf = [0; Self::ENCODED_LEN];
21713 let mut buf = if avail_len < Self::ENCODED_LEN {
21714 payload_buf[0..avail_len].copy_from_slice(__input);
21715 Bytes::new(&payload_buf)
21716 } else {
21717 Bytes::new(__input)
21718 };
21719 let mut __struct = Self::default();
21720 __struct.time_usec = buf.get_u64_le();
21721 __struct.roll = buf.get_f32_le();
21722 __struct.pitch = buf.get_f32_le();
21723 __struct.yaw = buf.get_f32_le();
21724 __struct.rollspeed = buf.get_f32_le();
21725 __struct.pitchspeed = buf.get_f32_le();
21726 __struct.yawspeed = buf.get_f32_le();
21727 __struct.lat = buf.get_i32_le();
21728 __struct.lon = buf.get_i32_le();
21729 __struct.alt = buf.get_i32_le();
21730 __struct.vx = buf.get_i16_le();
21731 __struct.vy = buf.get_i16_le();
21732 __struct.vz = buf.get_i16_le();
21733 __struct.xacc = buf.get_i16_le();
21734 __struct.yacc = buf.get_i16_le();
21735 __struct.zacc = buf.get_i16_le();
21736 Ok(__struct)
21737 }
21738 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21739 let mut __tmp = BytesMut::new(bytes);
21740 #[allow(clippy::absurd_extreme_comparisons)]
21741 #[allow(unused_comparisons)]
21742 if __tmp.remaining() < Self::ENCODED_LEN {
21743 panic!(
21744 "buffer is too small (need {} bytes, but got {})",
21745 Self::ENCODED_LEN,
21746 __tmp.remaining(),
21747 )
21748 }
21749 __tmp.put_u64_le(self.time_usec);
21750 __tmp.put_f32_le(self.roll);
21751 __tmp.put_f32_le(self.pitch);
21752 __tmp.put_f32_le(self.yaw);
21753 __tmp.put_f32_le(self.rollspeed);
21754 __tmp.put_f32_le(self.pitchspeed);
21755 __tmp.put_f32_le(self.yawspeed);
21756 __tmp.put_i32_le(self.lat);
21757 __tmp.put_i32_le(self.lon);
21758 __tmp.put_i32_le(self.alt);
21759 __tmp.put_i16_le(self.vx);
21760 __tmp.put_i16_le(self.vy);
21761 __tmp.put_i16_le(self.vz);
21762 __tmp.put_i16_le(self.xacc);
21763 __tmp.put_i16_le(self.yacc);
21764 __tmp.put_i16_le(self.zacc);
21765 if matches!(version, MavlinkVersion::V2) {
21766 let len = __tmp.len();
21767 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21768 } else {
21769 __tmp.len()
21770 }
21771 }
21772}
21773#[doc = "id: 148"]
21774#[doc = "Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE."]
21775#[derive(Debug, Clone, PartialEq)]
21776#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21777#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21778pub struct AUTOPILOT_VERSION_DATA {
21779 #[doc = "Bitmap of capabilities"]
21780 pub capabilities: MavProtocolCapability,
21781 #[doc = "UID if provided by hardware (see uid2)"]
21782 pub uid: u64,
21783 #[doc = "Firmware version number. The field must be encoded as 4 bytes, where each byte (shown from MSB to LSB) is part of a semantic version: (major) (minor) (patch) (FIRMWARE_VERSION_TYPE)."]
21784 pub flight_sw_version: u32,
21785 #[doc = "Middleware version number"]
21786 pub middleware_sw_version: u32,
21787 #[doc = "Operating system version number"]
21788 pub os_sw_version: u32,
21789 #[doc = "HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify <https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt>"]
21790 pub board_version: u32,
21791 #[doc = "ID of the board vendor"]
21792 pub vendor_id: u16,
21793 #[doc = "ID of the product"]
21794 pub product_id: u16,
21795 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
21796 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21797 pub flight_custom_version: [u8; 8],
21798 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
21799 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21800 pub middleware_custom_version: [u8; 8],
21801 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
21802 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21803 pub os_custom_version: [u8; 8],
21804 #[doc = "UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)"]
21805 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21806 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21807 pub uid2: [u8; 18],
21808}
21809impl AUTOPILOT_VERSION_DATA {
21810 pub const ENCODED_LEN: usize = 78usize;
21811 pub const DEFAULT: Self = Self {
21812 capabilities: MavProtocolCapability::DEFAULT,
21813 uid: 0_u64,
21814 flight_sw_version: 0_u32,
21815 middleware_sw_version: 0_u32,
21816 os_sw_version: 0_u32,
21817 board_version: 0_u32,
21818 vendor_id: 0_u16,
21819 product_id: 0_u16,
21820 flight_custom_version: [0_u8; 8usize],
21821 middleware_custom_version: [0_u8; 8usize],
21822 os_custom_version: [0_u8; 8usize],
21823 uid2: [0_u8; 18usize],
21824 };
21825 #[cfg(feature = "arbitrary")]
21826 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21827 use arbitrary::{Arbitrary, Unstructured};
21828 let mut buf = [0u8; 1024];
21829 rng.fill_bytes(&mut buf);
21830 let mut unstructured = Unstructured::new(&buf);
21831 Self::arbitrary(&mut unstructured).unwrap_or_default()
21832 }
21833}
21834impl Default for AUTOPILOT_VERSION_DATA {
21835 fn default() -> Self {
21836 Self::DEFAULT.clone()
21837 }
21838}
21839impl MessageData for AUTOPILOT_VERSION_DATA {
21840 type Message = MavMessage;
21841 const ID: u32 = 148u32;
21842 const NAME: &'static str = "AUTOPILOT_VERSION";
21843 const EXTRA_CRC: u8 = 178u8;
21844 const ENCODED_LEN: usize = 78usize;
21845 fn deser(
21846 _version: MavlinkVersion,
21847 __input: &[u8],
21848 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21849 let avail_len = __input.len();
21850 let mut payload_buf = [0; Self::ENCODED_LEN];
21851 let mut buf = if avail_len < Self::ENCODED_LEN {
21852 payload_buf[0..avail_len].copy_from_slice(__input);
21853 Bytes::new(&payload_buf)
21854 } else {
21855 Bytes::new(__input)
21856 };
21857 let mut __struct = Self::default();
21858 let tmp = buf.get_u64_le();
21859 __struct.capabilities = MavProtocolCapability::from_bits(
21860 tmp & MavProtocolCapability::all().bits(),
21861 )
21862 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
21863 flag_type: "MavProtocolCapability",
21864 value: tmp as u32,
21865 })?;
21866 __struct.uid = buf.get_u64_le();
21867 __struct.flight_sw_version = buf.get_u32_le();
21868 __struct.middleware_sw_version = buf.get_u32_le();
21869 __struct.os_sw_version = buf.get_u32_le();
21870 __struct.board_version = buf.get_u32_le();
21871 __struct.vendor_id = buf.get_u16_le();
21872 __struct.product_id = buf.get_u16_le();
21873 for v in &mut __struct.flight_custom_version {
21874 let val = buf.get_u8();
21875 *v = val;
21876 }
21877 for v in &mut __struct.middleware_custom_version {
21878 let val = buf.get_u8();
21879 *v = val;
21880 }
21881 for v in &mut __struct.os_custom_version {
21882 let val = buf.get_u8();
21883 *v = val;
21884 }
21885 for v in &mut __struct.uid2 {
21886 let val = buf.get_u8();
21887 *v = val;
21888 }
21889 Ok(__struct)
21890 }
21891 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21892 let mut __tmp = BytesMut::new(bytes);
21893 #[allow(clippy::absurd_extreme_comparisons)]
21894 #[allow(unused_comparisons)]
21895 if __tmp.remaining() < Self::ENCODED_LEN {
21896 panic!(
21897 "buffer is too small (need {} bytes, but got {})",
21898 Self::ENCODED_LEN,
21899 __tmp.remaining(),
21900 )
21901 }
21902 __tmp.put_u64_le(self.capabilities.bits());
21903 __tmp.put_u64_le(self.uid);
21904 __tmp.put_u32_le(self.flight_sw_version);
21905 __tmp.put_u32_le(self.middleware_sw_version);
21906 __tmp.put_u32_le(self.os_sw_version);
21907 __tmp.put_u32_le(self.board_version);
21908 __tmp.put_u16_le(self.vendor_id);
21909 __tmp.put_u16_le(self.product_id);
21910 for val in &self.flight_custom_version {
21911 __tmp.put_u8(*val);
21912 }
21913 for val in &self.middleware_custom_version {
21914 __tmp.put_u8(*val);
21915 }
21916 for val in &self.os_custom_version {
21917 __tmp.put_u8(*val);
21918 }
21919 for val in &self.uid2 {
21920 __tmp.put_u8(*val);
21921 }
21922 if matches!(version, MavlinkVersion::V2) {
21923 let len = __tmp.len();
21924 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21925 } else {
21926 __tmp.len()
21927 }
21928 }
21929}
21930#[doc = "id: 310"]
21931#[doc = "General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message \"uavcan.protocol.NodeStatus\" for the background information. The UAVCAN specification is available at <http://uavcan.org>."]
21932#[derive(Debug, Clone, PartialEq)]
21933#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21934#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21935pub struct UAVCAN_NODE_STATUS_DATA {
21936 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
21937 pub time_usec: u64,
21938 #[doc = "Time since the start-up of the node."]
21939 pub uptime_sec: u32,
21940 #[doc = "Vendor-specific status information."]
21941 pub vendor_specific_status_code: u16,
21942 #[doc = "Generalized node health status."]
21943 pub health: UavcanNodeHealth,
21944 #[doc = "Generalized operating mode."]
21945 pub mode: UavcanNodeMode,
21946 #[doc = "Not used currently."]
21947 pub sub_mode: u8,
21948}
21949impl UAVCAN_NODE_STATUS_DATA {
21950 pub const ENCODED_LEN: usize = 17usize;
21951 pub const DEFAULT: Self = Self {
21952 time_usec: 0_u64,
21953 uptime_sec: 0_u32,
21954 vendor_specific_status_code: 0_u16,
21955 health: UavcanNodeHealth::DEFAULT,
21956 mode: UavcanNodeMode::DEFAULT,
21957 sub_mode: 0_u8,
21958 };
21959 #[cfg(feature = "arbitrary")]
21960 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21961 use arbitrary::{Arbitrary, Unstructured};
21962 let mut buf = [0u8; 1024];
21963 rng.fill_bytes(&mut buf);
21964 let mut unstructured = Unstructured::new(&buf);
21965 Self::arbitrary(&mut unstructured).unwrap_or_default()
21966 }
21967}
21968impl Default for UAVCAN_NODE_STATUS_DATA {
21969 fn default() -> Self {
21970 Self::DEFAULT.clone()
21971 }
21972}
21973impl MessageData for UAVCAN_NODE_STATUS_DATA {
21974 type Message = MavMessage;
21975 const ID: u32 = 310u32;
21976 const NAME: &'static str = "UAVCAN_NODE_STATUS";
21977 const EXTRA_CRC: u8 = 28u8;
21978 const ENCODED_LEN: usize = 17usize;
21979 fn deser(
21980 _version: MavlinkVersion,
21981 __input: &[u8],
21982 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21983 let avail_len = __input.len();
21984 let mut payload_buf = [0; Self::ENCODED_LEN];
21985 let mut buf = if avail_len < Self::ENCODED_LEN {
21986 payload_buf[0..avail_len].copy_from_slice(__input);
21987 Bytes::new(&payload_buf)
21988 } else {
21989 Bytes::new(__input)
21990 };
21991 let mut __struct = Self::default();
21992 __struct.time_usec = buf.get_u64_le();
21993 __struct.uptime_sec = buf.get_u32_le();
21994 __struct.vendor_specific_status_code = buf.get_u16_le();
21995 let tmp = buf.get_u8();
21996 __struct.health =
21997 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21998 enum_type: "UavcanNodeHealth",
21999 value: tmp as u32,
22000 })?;
22001 let tmp = buf.get_u8();
22002 __struct.mode =
22003 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22004 enum_type: "UavcanNodeMode",
22005 value: tmp as u32,
22006 })?;
22007 __struct.sub_mode = buf.get_u8();
22008 Ok(__struct)
22009 }
22010 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22011 let mut __tmp = BytesMut::new(bytes);
22012 #[allow(clippy::absurd_extreme_comparisons)]
22013 #[allow(unused_comparisons)]
22014 if __tmp.remaining() < Self::ENCODED_LEN {
22015 panic!(
22016 "buffer is too small (need {} bytes, but got {})",
22017 Self::ENCODED_LEN,
22018 __tmp.remaining(),
22019 )
22020 }
22021 __tmp.put_u64_le(self.time_usec);
22022 __tmp.put_u32_le(self.uptime_sec);
22023 __tmp.put_u16_le(self.vendor_specific_status_code);
22024 __tmp.put_u8(self.health as u8);
22025 __tmp.put_u8(self.mode as u8);
22026 __tmp.put_u8(self.sub_mode);
22027 if matches!(version, MavlinkVersion::V2) {
22028 let len = __tmp.len();
22029 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22030 } else {
22031 __tmp.len()
22032 }
22033 }
22034}
22035#[doc = "id: 93"]
22036#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_CONTROLS."]
22037#[derive(Debug, Clone, PartialEq)]
22038#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22039#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22040pub struct HIL_ACTUATOR_CONTROLS_DATA {
22041 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
22042 pub time_usec: u64,
22043 #[doc = "Flags bitmask."]
22044 pub flags: HilActuatorControlsFlags,
22045 #[doc = "Control outputs -1 .. 1. Channel assignment depends on the simulated hardware."]
22046 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22047 pub controls: [f32; 16],
22048 #[doc = "System mode. Includes arming state."]
22049 pub mode: MavModeFlag,
22050}
22051impl HIL_ACTUATOR_CONTROLS_DATA {
22052 pub const ENCODED_LEN: usize = 81usize;
22053 pub const DEFAULT: Self = Self {
22054 time_usec: 0_u64,
22055 flags: HilActuatorControlsFlags::DEFAULT,
22056 controls: [0.0_f32; 16usize],
22057 mode: MavModeFlag::DEFAULT,
22058 };
22059 #[cfg(feature = "arbitrary")]
22060 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22061 use arbitrary::{Arbitrary, Unstructured};
22062 let mut buf = [0u8; 1024];
22063 rng.fill_bytes(&mut buf);
22064 let mut unstructured = Unstructured::new(&buf);
22065 Self::arbitrary(&mut unstructured).unwrap_or_default()
22066 }
22067}
22068impl Default for HIL_ACTUATOR_CONTROLS_DATA {
22069 fn default() -> Self {
22070 Self::DEFAULT.clone()
22071 }
22072}
22073impl MessageData for HIL_ACTUATOR_CONTROLS_DATA {
22074 type Message = MavMessage;
22075 const ID: u32 = 93u32;
22076 const NAME: &'static str = "HIL_ACTUATOR_CONTROLS";
22077 const EXTRA_CRC: u8 = 47u8;
22078 const ENCODED_LEN: usize = 81usize;
22079 fn deser(
22080 _version: MavlinkVersion,
22081 __input: &[u8],
22082 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22083 let avail_len = __input.len();
22084 let mut payload_buf = [0; Self::ENCODED_LEN];
22085 let mut buf = if avail_len < Self::ENCODED_LEN {
22086 payload_buf[0..avail_len].copy_from_slice(__input);
22087 Bytes::new(&payload_buf)
22088 } else {
22089 Bytes::new(__input)
22090 };
22091 let mut __struct = Self::default();
22092 __struct.time_usec = buf.get_u64_le();
22093 let tmp = buf.get_u64_le();
22094 __struct.flags =
22095 HilActuatorControlsFlags::from_bits(tmp & HilActuatorControlsFlags::all().bits())
22096 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22097 flag_type: "HilActuatorControlsFlags",
22098 value: tmp as u32,
22099 })?;
22100 for v in &mut __struct.controls {
22101 let val = buf.get_f32_le();
22102 *v = val;
22103 }
22104 let tmp = buf.get_u8();
22105 __struct.mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
22106 ::mavlink_core::error::ParserError::InvalidFlag {
22107 flag_type: "MavModeFlag",
22108 value: tmp as u32,
22109 },
22110 )?;
22111 Ok(__struct)
22112 }
22113 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22114 let mut __tmp = BytesMut::new(bytes);
22115 #[allow(clippy::absurd_extreme_comparisons)]
22116 #[allow(unused_comparisons)]
22117 if __tmp.remaining() < Self::ENCODED_LEN {
22118 panic!(
22119 "buffer is too small (need {} bytes, but got {})",
22120 Self::ENCODED_LEN,
22121 __tmp.remaining(),
22122 )
22123 }
22124 __tmp.put_u64_le(self.time_usec);
22125 __tmp.put_u64_le(self.flags.bits());
22126 for val in &self.controls {
22127 __tmp.put_f32_le(*val);
22128 }
22129 __tmp.put_u8(self.mode.bits());
22130 if matches!(version, MavlinkVersion::V2) {
22131 let len = __tmp.len();
22132 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22133 } else {
22134 __tmp.len()
22135 }
22136 }
22137}
22138#[doc = "id: 39"]
22139#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
22140#[derive(Debug, Clone, PartialEq)]
22141#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22142#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22143pub struct MISSION_ITEM_DATA {
22144 #[doc = "PARAM1, see MAV_CMD enum"]
22145 pub param1: f32,
22146 #[doc = "PARAM2, see MAV_CMD enum"]
22147 pub param2: f32,
22148 #[doc = "PARAM3, see MAV_CMD enum"]
22149 pub param3: f32,
22150 #[doc = "PARAM4, see MAV_CMD enum"]
22151 pub param4: f32,
22152 #[doc = "PARAM5 / local: X coordinate, global: latitude"]
22153 pub x: f32,
22154 #[doc = "PARAM6 / local: Y coordinate, global: longitude"]
22155 pub y: f32,
22156 #[doc = "PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame)."]
22157 pub z: f32,
22158 #[doc = "Sequence"]
22159 pub seq: u16,
22160 #[doc = "The scheduled action for the waypoint."]
22161 pub command: MavCmd,
22162 #[doc = "System ID"]
22163 pub target_system: u8,
22164 #[doc = "Component ID"]
22165 pub target_component: u8,
22166 #[doc = "The coordinate system of the waypoint."]
22167 pub frame: MavFrame,
22168 #[doc = "false:0, true:1"]
22169 pub current: u8,
22170 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
22171 pub autocontinue: u8,
22172 #[doc = "Mission type."]
22173 #[cfg_attr(feature = "serde", serde(default))]
22174 pub mission_type: MavMissionType,
22175}
22176impl MISSION_ITEM_DATA {
22177 pub const ENCODED_LEN: usize = 38usize;
22178 pub const DEFAULT: Self = Self {
22179 param1: 0.0_f32,
22180 param2: 0.0_f32,
22181 param3: 0.0_f32,
22182 param4: 0.0_f32,
22183 x: 0.0_f32,
22184 y: 0.0_f32,
22185 z: 0.0_f32,
22186 seq: 0_u16,
22187 command: MavCmd::DEFAULT,
22188 target_system: 0_u8,
22189 target_component: 0_u8,
22190 frame: MavFrame::DEFAULT,
22191 current: 0_u8,
22192 autocontinue: 0_u8,
22193 mission_type: MavMissionType::DEFAULT,
22194 };
22195 #[cfg(feature = "arbitrary")]
22196 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22197 use arbitrary::{Arbitrary, Unstructured};
22198 let mut buf = [0u8; 1024];
22199 rng.fill_bytes(&mut buf);
22200 let mut unstructured = Unstructured::new(&buf);
22201 Self::arbitrary(&mut unstructured).unwrap_or_default()
22202 }
22203}
22204impl Default for MISSION_ITEM_DATA {
22205 fn default() -> Self {
22206 Self::DEFAULT.clone()
22207 }
22208}
22209impl MessageData for MISSION_ITEM_DATA {
22210 type Message = MavMessage;
22211 const ID: u32 = 39u32;
22212 const NAME: &'static str = "MISSION_ITEM";
22213 const EXTRA_CRC: u8 = 254u8;
22214 const ENCODED_LEN: usize = 38usize;
22215 fn deser(
22216 _version: MavlinkVersion,
22217 __input: &[u8],
22218 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22219 let avail_len = __input.len();
22220 let mut payload_buf = [0; Self::ENCODED_LEN];
22221 let mut buf = if avail_len < Self::ENCODED_LEN {
22222 payload_buf[0..avail_len].copy_from_slice(__input);
22223 Bytes::new(&payload_buf)
22224 } else {
22225 Bytes::new(__input)
22226 };
22227 let mut __struct = Self::default();
22228 __struct.param1 = buf.get_f32_le();
22229 __struct.param2 = buf.get_f32_le();
22230 __struct.param3 = buf.get_f32_le();
22231 __struct.param4 = buf.get_f32_le();
22232 __struct.x = buf.get_f32_le();
22233 __struct.y = buf.get_f32_le();
22234 __struct.z = buf.get_f32_le();
22235 __struct.seq = buf.get_u16_le();
22236 let tmp = buf.get_u16_le();
22237 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
22238 ::mavlink_core::error::ParserError::InvalidEnum {
22239 enum_type: "MavCmd",
22240 value: tmp as u32,
22241 },
22242 )?;
22243 __struct.target_system = buf.get_u8();
22244 __struct.target_component = buf.get_u8();
22245 let tmp = buf.get_u8();
22246 __struct.frame =
22247 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22248 enum_type: "MavFrame",
22249 value: tmp as u32,
22250 })?;
22251 __struct.current = buf.get_u8();
22252 __struct.autocontinue = buf.get_u8();
22253 let tmp = buf.get_u8();
22254 __struct.mission_type =
22255 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22256 enum_type: "MavMissionType",
22257 value: tmp as u32,
22258 })?;
22259 Ok(__struct)
22260 }
22261 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22262 let mut __tmp = BytesMut::new(bytes);
22263 #[allow(clippy::absurd_extreme_comparisons)]
22264 #[allow(unused_comparisons)]
22265 if __tmp.remaining() < Self::ENCODED_LEN {
22266 panic!(
22267 "buffer is too small (need {} bytes, but got {})",
22268 Self::ENCODED_LEN,
22269 __tmp.remaining(),
22270 )
22271 }
22272 __tmp.put_f32_le(self.param1);
22273 __tmp.put_f32_le(self.param2);
22274 __tmp.put_f32_le(self.param3);
22275 __tmp.put_f32_le(self.param4);
22276 __tmp.put_f32_le(self.x);
22277 __tmp.put_f32_le(self.y);
22278 __tmp.put_f32_le(self.z);
22279 __tmp.put_u16_le(self.seq);
22280 __tmp.put_u16_le(self.command as u16);
22281 __tmp.put_u8(self.target_system);
22282 __tmp.put_u8(self.target_component);
22283 __tmp.put_u8(self.frame as u8);
22284 __tmp.put_u8(self.current);
22285 __tmp.put_u8(self.autocontinue);
22286 __tmp.put_u8(self.mission_type as u8);
22287 if matches!(version, MavlinkVersion::V2) {
22288 let len = __tmp.len();
22289 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22290 } else {
22291 __tmp.len()
22292 }
22293 }
22294}
22295#[doc = "id: 340"]
22296#[doc = "The global position resulting from GPS and sensor fusion."]
22297#[derive(Debug, Clone, PartialEq)]
22298#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22299#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22300pub struct UTM_GLOBAL_POSITION_DATA {
22301 #[doc = "Time of applicability of position (microseconds since UNIX epoch)."]
22302 pub time: u64,
22303 #[doc = "Latitude (WGS84)"]
22304 pub lat: i32,
22305 #[doc = "Longitude (WGS84)"]
22306 pub lon: i32,
22307 #[doc = "Altitude (WGS84)"]
22308 pub alt: i32,
22309 #[doc = "Altitude above ground"]
22310 pub relative_alt: i32,
22311 #[doc = "Next waypoint, latitude (WGS84)"]
22312 pub next_lat: i32,
22313 #[doc = "Next waypoint, longitude (WGS84)"]
22314 pub next_lon: i32,
22315 #[doc = "Next waypoint, altitude (WGS84)"]
22316 pub next_alt: i32,
22317 #[doc = "Ground X speed (latitude, positive north)"]
22318 pub vx: i16,
22319 #[doc = "Ground Y speed (longitude, positive east)"]
22320 pub vy: i16,
22321 #[doc = "Ground Z speed (altitude, positive down)"]
22322 pub vz: i16,
22323 #[doc = "Horizontal position uncertainty (standard deviation)"]
22324 pub h_acc: u16,
22325 #[doc = "Altitude uncertainty (standard deviation)"]
22326 pub v_acc: u16,
22327 #[doc = "Speed uncertainty (standard deviation)"]
22328 pub vel_acc: u16,
22329 #[doc = "Time until next update. Set to 0 if unknown or in data driven mode."]
22330 pub update_rate: u16,
22331 #[doc = "Unique UAS ID."]
22332 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22333 pub uas_id: [u8; 18],
22334 #[doc = "Flight state"]
22335 pub flight_state: UtmFlightState,
22336 #[doc = "Bitwise OR combination of the data available flags."]
22337 pub flags: UtmDataAvailFlags,
22338}
22339impl UTM_GLOBAL_POSITION_DATA {
22340 pub const ENCODED_LEN: usize = 70usize;
22341 pub const DEFAULT: Self = Self {
22342 time: 0_u64,
22343 lat: 0_i32,
22344 lon: 0_i32,
22345 alt: 0_i32,
22346 relative_alt: 0_i32,
22347 next_lat: 0_i32,
22348 next_lon: 0_i32,
22349 next_alt: 0_i32,
22350 vx: 0_i16,
22351 vy: 0_i16,
22352 vz: 0_i16,
22353 h_acc: 0_u16,
22354 v_acc: 0_u16,
22355 vel_acc: 0_u16,
22356 update_rate: 0_u16,
22357 uas_id: [0_u8; 18usize],
22358 flight_state: UtmFlightState::DEFAULT,
22359 flags: UtmDataAvailFlags::DEFAULT,
22360 };
22361 #[cfg(feature = "arbitrary")]
22362 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22363 use arbitrary::{Arbitrary, Unstructured};
22364 let mut buf = [0u8; 1024];
22365 rng.fill_bytes(&mut buf);
22366 let mut unstructured = Unstructured::new(&buf);
22367 Self::arbitrary(&mut unstructured).unwrap_or_default()
22368 }
22369}
22370impl Default for UTM_GLOBAL_POSITION_DATA {
22371 fn default() -> Self {
22372 Self::DEFAULT.clone()
22373 }
22374}
22375impl MessageData for UTM_GLOBAL_POSITION_DATA {
22376 type Message = MavMessage;
22377 const ID: u32 = 340u32;
22378 const NAME: &'static str = "UTM_GLOBAL_POSITION";
22379 const EXTRA_CRC: u8 = 99u8;
22380 const ENCODED_LEN: usize = 70usize;
22381 fn deser(
22382 _version: MavlinkVersion,
22383 __input: &[u8],
22384 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22385 let avail_len = __input.len();
22386 let mut payload_buf = [0; Self::ENCODED_LEN];
22387 let mut buf = if avail_len < Self::ENCODED_LEN {
22388 payload_buf[0..avail_len].copy_from_slice(__input);
22389 Bytes::new(&payload_buf)
22390 } else {
22391 Bytes::new(__input)
22392 };
22393 let mut __struct = Self::default();
22394 __struct.time = buf.get_u64_le();
22395 __struct.lat = buf.get_i32_le();
22396 __struct.lon = buf.get_i32_le();
22397 __struct.alt = buf.get_i32_le();
22398 __struct.relative_alt = buf.get_i32_le();
22399 __struct.next_lat = buf.get_i32_le();
22400 __struct.next_lon = buf.get_i32_le();
22401 __struct.next_alt = buf.get_i32_le();
22402 __struct.vx = buf.get_i16_le();
22403 __struct.vy = buf.get_i16_le();
22404 __struct.vz = buf.get_i16_le();
22405 __struct.h_acc = buf.get_u16_le();
22406 __struct.v_acc = buf.get_u16_le();
22407 __struct.vel_acc = buf.get_u16_le();
22408 __struct.update_rate = buf.get_u16_le();
22409 for v in &mut __struct.uas_id {
22410 let val = buf.get_u8();
22411 *v = val;
22412 }
22413 let tmp = buf.get_u8();
22414 __struct.flight_state =
22415 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22416 enum_type: "UtmFlightState",
22417 value: tmp as u32,
22418 })?;
22419 let tmp = buf.get_u8();
22420 __struct.flags = UtmDataAvailFlags::from_bits(tmp & UtmDataAvailFlags::all().bits())
22421 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22422 flag_type: "UtmDataAvailFlags",
22423 value: tmp as u32,
22424 })?;
22425 Ok(__struct)
22426 }
22427 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22428 let mut __tmp = BytesMut::new(bytes);
22429 #[allow(clippy::absurd_extreme_comparisons)]
22430 #[allow(unused_comparisons)]
22431 if __tmp.remaining() < Self::ENCODED_LEN {
22432 panic!(
22433 "buffer is too small (need {} bytes, but got {})",
22434 Self::ENCODED_LEN,
22435 __tmp.remaining(),
22436 )
22437 }
22438 __tmp.put_u64_le(self.time);
22439 __tmp.put_i32_le(self.lat);
22440 __tmp.put_i32_le(self.lon);
22441 __tmp.put_i32_le(self.alt);
22442 __tmp.put_i32_le(self.relative_alt);
22443 __tmp.put_i32_le(self.next_lat);
22444 __tmp.put_i32_le(self.next_lon);
22445 __tmp.put_i32_le(self.next_alt);
22446 __tmp.put_i16_le(self.vx);
22447 __tmp.put_i16_le(self.vy);
22448 __tmp.put_i16_le(self.vz);
22449 __tmp.put_u16_le(self.h_acc);
22450 __tmp.put_u16_le(self.v_acc);
22451 __tmp.put_u16_le(self.vel_acc);
22452 __tmp.put_u16_le(self.update_rate);
22453 for val in &self.uas_id {
22454 __tmp.put_u8(*val);
22455 }
22456 __tmp.put_u8(self.flight_state as u8);
22457 __tmp.put_u8(self.flags.bits());
22458 if matches!(version, MavlinkVersion::V2) {
22459 let len = __tmp.len();
22460 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22461 } else {
22462 __tmp.len()
22463 }
22464 }
22465}
22466#[doc = "id: 77"]
22467#[doc = "Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
22468#[derive(Debug, Clone, PartialEq)]
22469#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22470#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22471pub struct COMMAND_ACK_DATA {
22472 #[doc = "Command ID (of acknowledged command)."]
22473 pub command: MavCmd,
22474 #[doc = "Result of command."]
22475 pub result: MavResult,
22476 #[doc = "The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown."]
22477 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22478 pub progress: u8,
22479 #[doc = "Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate \"unused\" or \"unknown\")."]
22480 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22481 pub result_param2: i32,
22482 #[doc = "System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
22483 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22484 pub target_system: u8,
22485 #[doc = "Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
22486 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22487 pub target_component: u8,
22488}
22489impl COMMAND_ACK_DATA {
22490 pub const ENCODED_LEN: usize = 10usize;
22491 pub const DEFAULT: Self = Self {
22492 command: MavCmd::DEFAULT,
22493 result: MavResult::DEFAULT,
22494 progress: 0_u8,
22495 result_param2: 0_i32,
22496 target_system: 0_u8,
22497 target_component: 0_u8,
22498 };
22499 #[cfg(feature = "arbitrary")]
22500 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22501 use arbitrary::{Arbitrary, Unstructured};
22502 let mut buf = [0u8; 1024];
22503 rng.fill_bytes(&mut buf);
22504 let mut unstructured = Unstructured::new(&buf);
22505 Self::arbitrary(&mut unstructured).unwrap_or_default()
22506 }
22507}
22508impl Default for COMMAND_ACK_DATA {
22509 fn default() -> Self {
22510 Self::DEFAULT.clone()
22511 }
22512}
22513impl MessageData for COMMAND_ACK_DATA {
22514 type Message = MavMessage;
22515 const ID: u32 = 77u32;
22516 const NAME: &'static str = "COMMAND_ACK";
22517 const EXTRA_CRC: u8 = 143u8;
22518 const ENCODED_LEN: usize = 10usize;
22519 fn deser(
22520 _version: MavlinkVersion,
22521 __input: &[u8],
22522 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22523 let avail_len = __input.len();
22524 let mut payload_buf = [0; Self::ENCODED_LEN];
22525 let mut buf = if avail_len < Self::ENCODED_LEN {
22526 payload_buf[0..avail_len].copy_from_slice(__input);
22527 Bytes::new(&payload_buf)
22528 } else {
22529 Bytes::new(__input)
22530 };
22531 let mut __struct = Self::default();
22532 let tmp = buf.get_u16_le();
22533 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
22534 ::mavlink_core::error::ParserError::InvalidEnum {
22535 enum_type: "MavCmd",
22536 value: tmp as u32,
22537 },
22538 )?;
22539 let tmp = buf.get_u8();
22540 __struct.result =
22541 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22542 enum_type: "MavResult",
22543 value: tmp as u32,
22544 })?;
22545 __struct.progress = buf.get_u8();
22546 __struct.result_param2 = buf.get_i32_le();
22547 __struct.target_system = buf.get_u8();
22548 __struct.target_component = buf.get_u8();
22549 Ok(__struct)
22550 }
22551 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22552 let mut __tmp = BytesMut::new(bytes);
22553 #[allow(clippy::absurd_extreme_comparisons)]
22554 #[allow(unused_comparisons)]
22555 if __tmp.remaining() < Self::ENCODED_LEN {
22556 panic!(
22557 "buffer is too small (need {} bytes, but got {})",
22558 Self::ENCODED_LEN,
22559 __tmp.remaining(),
22560 )
22561 }
22562 __tmp.put_u16_le(self.command as u16);
22563 __tmp.put_u8(self.result as u8);
22564 __tmp.put_u8(self.progress);
22565 __tmp.put_i32_le(self.result_param2);
22566 __tmp.put_u8(self.target_system);
22567 __tmp.put_u8(self.target_component);
22568 if matches!(version, MavlinkVersion::V2) {
22569 let len = __tmp.len();
22570 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22571 } else {
22572 __tmp.len()
22573 }
22574 }
22575}
22576#[doc = "id: 231"]
22577#[doc = "Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD)."]
22578#[derive(Debug, Clone, PartialEq)]
22579#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22580#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22581pub struct WIND_COV_DATA {
22582 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
22583 pub time_usec: u64,
22584 #[doc = "Wind in North (NED) direction (NAN if unknown)"]
22585 pub wind_x: f32,
22586 #[doc = "Wind in East (NED) direction (NAN if unknown)"]
22587 pub wind_y: f32,
22588 #[doc = "Wind in down (NED) direction (NAN if unknown)"]
22589 pub wind_z: f32,
22590 #[doc = "Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
22591 pub var_horiz: f32,
22592 #[doc = "Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
22593 pub var_vert: f32,
22594 #[doc = "Altitude (MSL) that this measurement was taken at (NAN if unknown)"]
22595 pub wind_alt: f32,
22596 #[doc = "Horizontal speed 1-STD accuracy (0 if unknown)"]
22597 pub horiz_accuracy: f32,
22598 #[doc = "Vertical speed 1-STD accuracy (0 if unknown)"]
22599 pub vert_accuracy: f32,
22600}
22601impl WIND_COV_DATA {
22602 pub const ENCODED_LEN: usize = 40usize;
22603 pub const DEFAULT: Self = Self {
22604 time_usec: 0_u64,
22605 wind_x: 0.0_f32,
22606 wind_y: 0.0_f32,
22607 wind_z: 0.0_f32,
22608 var_horiz: 0.0_f32,
22609 var_vert: 0.0_f32,
22610 wind_alt: 0.0_f32,
22611 horiz_accuracy: 0.0_f32,
22612 vert_accuracy: 0.0_f32,
22613 };
22614 #[cfg(feature = "arbitrary")]
22615 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22616 use arbitrary::{Arbitrary, Unstructured};
22617 let mut buf = [0u8; 1024];
22618 rng.fill_bytes(&mut buf);
22619 let mut unstructured = Unstructured::new(&buf);
22620 Self::arbitrary(&mut unstructured).unwrap_or_default()
22621 }
22622}
22623impl Default for WIND_COV_DATA {
22624 fn default() -> Self {
22625 Self::DEFAULT.clone()
22626 }
22627}
22628impl MessageData for WIND_COV_DATA {
22629 type Message = MavMessage;
22630 const ID: u32 = 231u32;
22631 const NAME: &'static str = "WIND_COV";
22632 const EXTRA_CRC: u8 = 105u8;
22633 const ENCODED_LEN: usize = 40usize;
22634 fn deser(
22635 _version: MavlinkVersion,
22636 __input: &[u8],
22637 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22638 let avail_len = __input.len();
22639 let mut payload_buf = [0; Self::ENCODED_LEN];
22640 let mut buf = if avail_len < Self::ENCODED_LEN {
22641 payload_buf[0..avail_len].copy_from_slice(__input);
22642 Bytes::new(&payload_buf)
22643 } else {
22644 Bytes::new(__input)
22645 };
22646 let mut __struct = Self::default();
22647 __struct.time_usec = buf.get_u64_le();
22648 __struct.wind_x = buf.get_f32_le();
22649 __struct.wind_y = buf.get_f32_le();
22650 __struct.wind_z = buf.get_f32_le();
22651 __struct.var_horiz = buf.get_f32_le();
22652 __struct.var_vert = buf.get_f32_le();
22653 __struct.wind_alt = buf.get_f32_le();
22654 __struct.horiz_accuracy = buf.get_f32_le();
22655 __struct.vert_accuracy = buf.get_f32_le();
22656 Ok(__struct)
22657 }
22658 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22659 let mut __tmp = BytesMut::new(bytes);
22660 #[allow(clippy::absurd_extreme_comparisons)]
22661 #[allow(unused_comparisons)]
22662 if __tmp.remaining() < Self::ENCODED_LEN {
22663 panic!(
22664 "buffer is too small (need {} bytes, but got {})",
22665 Self::ENCODED_LEN,
22666 __tmp.remaining(),
22667 )
22668 }
22669 __tmp.put_u64_le(self.time_usec);
22670 __tmp.put_f32_le(self.wind_x);
22671 __tmp.put_f32_le(self.wind_y);
22672 __tmp.put_f32_le(self.wind_z);
22673 __tmp.put_f32_le(self.var_horiz);
22674 __tmp.put_f32_le(self.var_vert);
22675 __tmp.put_f32_le(self.wind_alt);
22676 __tmp.put_f32_le(self.horiz_accuracy);
22677 __tmp.put_f32_le(self.vert_accuracy);
22678 if matches!(version, MavlinkVersion::V2) {
22679 let len = __tmp.len();
22680 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22681 } else {
22682 __tmp.len()
22683 }
22684 }
22685}
22686#[doc = "id: 254"]
22687#[doc = "Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N."]
22688#[derive(Debug, Clone, PartialEq)]
22689#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22690#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22691pub struct DEBUG_DATA {
22692 #[doc = "Timestamp (time since system boot)."]
22693 pub time_boot_ms: u32,
22694 #[doc = "DEBUG value"]
22695 pub value: f32,
22696 #[doc = "index of debug variable"]
22697 pub ind: u8,
22698}
22699impl DEBUG_DATA {
22700 pub const ENCODED_LEN: usize = 9usize;
22701 pub const DEFAULT: Self = Self {
22702 time_boot_ms: 0_u32,
22703 value: 0.0_f32,
22704 ind: 0_u8,
22705 };
22706 #[cfg(feature = "arbitrary")]
22707 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22708 use arbitrary::{Arbitrary, Unstructured};
22709 let mut buf = [0u8; 1024];
22710 rng.fill_bytes(&mut buf);
22711 let mut unstructured = Unstructured::new(&buf);
22712 Self::arbitrary(&mut unstructured).unwrap_or_default()
22713 }
22714}
22715impl Default for DEBUG_DATA {
22716 fn default() -> Self {
22717 Self::DEFAULT.clone()
22718 }
22719}
22720impl MessageData for DEBUG_DATA {
22721 type Message = MavMessage;
22722 const ID: u32 = 254u32;
22723 const NAME: &'static str = "DEBUG";
22724 const EXTRA_CRC: u8 = 46u8;
22725 const ENCODED_LEN: usize = 9usize;
22726 fn deser(
22727 _version: MavlinkVersion,
22728 __input: &[u8],
22729 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22730 let avail_len = __input.len();
22731 let mut payload_buf = [0; Self::ENCODED_LEN];
22732 let mut buf = if avail_len < Self::ENCODED_LEN {
22733 payload_buf[0..avail_len].copy_from_slice(__input);
22734 Bytes::new(&payload_buf)
22735 } else {
22736 Bytes::new(__input)
22737 };
22738 let mut __struct = Self::default();
22739 __struct.time_boot_ms = buf.get_u32_le();
22740 __struct.value = buf.get_f32_le();
22741 __struct.ind = buf.get_u8();
22742 Ok(__struct)
22743 }
22744 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22745 let mut __tmp = BytesMut::new(bytes);
22746 #[allow(clippy::absurd_extreme_comparisons)]
22747 #[allow(unused_comparisons)]
22748 if __tmp.remaining() < Self::ENCODED_LEN {
22749 panic!(
22750 "buffer is too small (need {} bytes, but got {})",
22751 Self::ENCODED_LEN,
22752 __tmp.remaining(),
22753 )
22754 }
22755 __tmp.put_u32_le(self.time_boot_ms);
22756 __tmp.put_f32_le(self.value);
22757 __tmp.put_u8(self.ind);
22758 if matches!(version, MavlinkVersion::V2) {
22759 let len = __tmp.len();
22760 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22761 } else {
22762 __tmp.len()
22763 }
22764 }
22765}
22766#[doc = "id: 268"]
22767#[doc = "An ack for a LOGGING_DATA_ACKED message."]
22768#[derive(Debug, Clone, PartialEq)]
22769#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22770#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22771pub struct LOGGING_ACK_DATA {
22772 #[doc = "sequence number (must match the one in LOGGING_DATA_ACKED)"]
22773 pub sequence: u16,
22774 #[doc = "system ID of the target"]
22775 pub target_system: u8,
22776 #[doc = "component ID of the target"]
22777 pub target_component: u8,
22778}
22779impl LOGGING_ACK_DATA {
22780 pub const ENCODED_LEN: usize = 4usize;
22781 pub const DEFAULT: Self = Self {
22782 sequence: 0_u16,
22783 target_system: 0_u8,
22784 target_component: 0_u8,
22785 };
22786 #[cfg(feature = "arbitrary")]
22787 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22788 use arbitrary::{Arbitrary, Unstructured};
22789 let mut buf = [0u8; 1024];
22790 rng.fill_bytes(&mut buf);
22791 let mut unstructured = Unstructured::new(&buf);
22792 Self::arbitrary(&mut unstructured).unwrap_or_default()
22793 }
22794}
22795impl Default for LOGGING_ACK_DATA {
22796 fn default() -> Self {
22797 Self::DEFAULT.clone()
22798 }
22799}
22800impl MessageData for LOGGING_ACK_DATA {
22801 type Message = MavMessage;
22802 const ID: u32 = 268u32;
22803 const NAME: &'static str = "LOGGING_ACK";
22804 const EXTRA_CRC: u8 = 14u8;
22805 const ENCODED_LEN: usize = 4usize;
22806 fn deser(
22807 _version: MavlinkVersion,
22808 __input: &[u8],
22809 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22810 let avail_len = __input.len();
22811 let mut payload_buf = [0; Self::ENCODED_LEN];
22812 let mut buf = if avail_len < Self::ENCODED_LEN {
22813 payload_buf[0..avail_len].copy_from_slice(__input);
22814 Bytes::new(&payload_buf)
22815 } else {
22816 Bytes::new(__input)
22817 };
22818 let mut __struct = Self::default();
22819 __struct.sequence = buf.get_u16_le();
22820 __struct.target_system = buf.get_u8();
22821 __struct.target_component = buf.get_u8();
22822 Ok(__struct)
22823 }
22824 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22825 let mut __tmp = BytesMut::new(bytes);
22826 #[allow(clippy::absurd_extreme_comparisons)]
22827 #[allow(unused_comparisons)]
22828 if __tmp.remaining() < Self::ENCODED_LEN {
22829 panic!(
22830 "buffer is too small (need {} bytes, but got {})",
22831 Self::ENCODED_LEN,
22832 __tmp.remaining(),
22833 )
22834 }
22835 __tmp.put_u16_le(self.sequence);
22836 __tmp.put_u8(self.target_system);
22837 __tmp.put_u8(self.target_component);
22838 if matches!(version, MavlinkVersion::V2) {
22839 let len = __tmp.len();
22840 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22841 } else {
22842 __tmp.len()
22843 }
22844 }
22845}
22846#[doc = "id: 435"]
22847#[doc = "Information about a flight mode. The message can be enumerated to get information for all modes, or requested for a particular mode, using MAV_CMD_REQUEST_MESSAGE. Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. The modes must be available/settable for the current vehicle/frame type. Each mode should only be emitted once (even if it is both standard and custom). Note that the current mode should be emitted in CURRENT_MODE, and that if the mode list can change then AVAILABLE_MODES_MONITOR must be emitted on first change and subsequently streamed. See <https://mavlink.io/en/services/standard_modes.html>."]
22848#[derive(Debug, Clone, PartialEq)]
22849#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22850#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22851pub struct AVAILABLE_MODES_DATA {
22852 #[doc = "A bitfield for use for autopilot-specific flags"]
22853 pub custom_mode: u32,
22854 #[doc = "Mode properties."]
22855 pub properties: MavModeProperty,
22856 #[doc = "The total number of available modes for the current vehicle type."]
22857 pub number_modes: u8,
22858 #[doc = "The current mode index within number_modes, indexed from 1. The index is not guaranteed to be persistent, and may change between reboots or if the set of modes change."]
22859 pub mode_index: u8,
22860 #[doc = "Standard mode."]
22861 pub standard_mode: MavStandardMode,
22862 #[doc = "Name of custom mode, with null termination character. Should be omitted for standard modes."]
22863 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22864 pub mode_name: [u8; 35],
22865}
22866impl AVAILABLE_MODES_DATA {
22867 pub const ENCODED_LEN: usize = 46usize;
22868 pub const DEFAULT: Self = Self {
22869 custom_mode: 0_u32,
22870 properties: MavModeProperty::DEFAULT,
22871 number_modes: 0_u8,
22872 mode_index: 0_u8,
22873 standard_mode: MavStandardMode::DEFAULT,
22874 mode_name: [0_u8; 35usize],
22875 };
22876 #[cfg(feature = "arbitrary")]
22877 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22878 use arbitrary::{Arbitrary, Unstructured};
22879 let mut buf = [0u8; 1024];
22880 rng.fill_bytes(&mut buf);
22881 let mut unstructured = Unstructured::new(&buf);
22882 Self::arbitrary(&mut unstructured).unwrap_or_default()
22883 }
22884}
22885impl Default for AVAILABLE_MODES_DATA {
22886 fn default() -> Self {
22887 Self::DEFAULT.clone()
22888 }
22889}
22890impl MessageData for AVAILABLE_MODES_DATA {
22891 type Message = MavMessage;
22892 const ID: u32 = 435u32;
22893 const NAME: &'static str = "AVAILABLE_MODES";
22894 const EXTRA_CRC: u8 = 134u8;
22895 const ENCODED_LEN: usize = 46usize;
22896 fn deser(
22897 _version: MavlinkVersion,
22898 __input: &[u8],
22899 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22900 let avail_len = __input.len();
22901 let mut payload_buf = [0; Self::ENCODED_LEN];
22902 let mut buf = if avail_len < Self::ENCODED_LEN {
22903 payload_buf[0..avail_len].copy_from_slice(__input);
22904 Bytes::new(&payload_buf)
22905 } else {
22906 Bytes::new(__input)
22907 };
22908 let mut __struct = Self::default();
22909 __struct.custom_mode = buf.get_u32_le();
22910 let tmp = buf.get_u32_le();
22911 __struct.properties = MavModeProperty::from_bits(tmp & MavModeProperty::all().bits())
22912 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22913 flag_type: "MavModeProperty",
22914 value: tmp as u32,
22915 })?;
22916 __struct.number_modes = buf.get_u8();
22917 __struct.mode_index = buf.get_u8();
22918 let tmp = buf.get_u8();
22919 __struct.standard_mode =
22920 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22921 enum_type: "MavStandardMode",
22922 value: tmp as u32,
22923 })?;
22924 for v in &mut __struct.mode_name {
22925 let val = buf.get_u8();
22926 *v = val;
22927 }
22928 Ok(__struct)
22929 }
22930 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22931 let mut __tmp = BytesMut::new(bytes);
22932 #[allow(clippy::absurd_extreme_comparisons)]
22933 #[allow(unused_comparisons)]
22934 if __tmp.remaining() < Self::ENCODED_LEN {
22935 panic!(
22936 "buffer is too small (need {} bytes, but got {})",
22937 Self::ENCODED_LEN,
22938 __tmp.remaining(),
22939 )
22940 }
22941 __tmp.put_u32_le(self.custom_mode);
22942 __tmp.put_u32_le(self.properties.bits());
22943 __tmp.put_u8(self.number_modes);
22944 __tmp.put_u8(self.mode_index);
22945 __tmp.put_u8(self.standard_mode as u8);
22946 for val in &self.mode_name {
22947 __tmp.put_u8(*val);
22948 }
22949 if matches!(version, MavlinkVersion::V2) {
22950 let len = __tmp.len();
22951 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22952 } else {
22953 __tmp.len()
22954 }
22955 }
22956}
22957#[doc = "id: 261"]
22958#[doc = "Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc."]
22959#[derive(Debug, Clone, PartialEq)]
22960#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22961#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22962pub struct STORAGE_INFORMATION_DATA {
22963 #[doc = "Timestamp (time since system boot)."]
22964 pub time_boot_ms: u32,
22965 #[doc = "Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
22966 pub total_capacity: f32,
22967 #[doc = "Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
22968 pub used_capacity: f32,
22969 #[doc = "Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
22970 pub available_capacity: f32,
22971 #[doc = "Read speed."]
22972 pub read_speed: f32,
22973 #[doc = "Write speed."]
22974 pub write_speed: f32,
22975 #[doc = "Storage ID (1 for first, 2 for second, etc.)"]
22976 pub storage_id: u8,
22977 #[doc = "Number of storage devices"]
22978 pub storage_count: u8,
22979 #[doc = "Status of storage"]
22980 pub status: StorageStatus,
22981 #[doc = "Type of storage"]
22982 #[cfg_attr(feature = "serde", serde(default))]
22983 pub mavtype: StorageType,
22984 #[doc = "Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user."]
22985 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22986 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22987 pub name: [u8; 32],
22988 #[doc = "Flags indicating whether this instance is preferred storage for photos, videos, etc. Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types."]
22989 #[cfg_attr(feature = "serde", serde(default))]
22990 pub storage_usage: StorageUsageFlag,
22991}
22992impl STORAGE_INFORMATION_DATA {
22993 pub const ENCODED_LEN: usize = 61usize;
22994 pub const DEFAULT: Self = Self {
22995 time_boot_ms: 0_u32,
22996 total_capacity: 0.0_f32,
22997 used_capacity: 0.0_f32,
22998 available_capacity: 0.0_f32,
22999 read_speed: 0.0_f32,
23000 write_speed: 0.0_f32,
23001 storage_id: 0_u8,
23002 storage_count: 0_u8,
23003 status: StorageStatus::DEFAULT,
23004 mavtype: StorageType::DEFAULT,
23005 name: [0_u8; 32usize],
23006 storage_usage: StorageUsageFlag::DEFAULT,
23007 };
23008 #[cfg(feature = "arbitrary")]
23009 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23010 use arbitrary::{Arbitrary, Unstructured};
23011 let mut buf = [0u8; 1024];
23012 rng.fill_bytes(&mut buf);
23013 let mut unstructured = Unstructured::new(&buf);
23014 Self::arbitrary(&mut unstructured).unwrap_or_default()
23015 }
23016}
23017impl Default for STORAGE_INFORMATION_DATA {
23018 fn default() -> Self {
23019 Self::DEFAULT.clone()
23020 }
23021}
23022impl MessageData for STORAGE_INFORMATION_DATA {
23023 type Message = MavMessage;
23024 const ID: u32 = 261u32;
23025 const NAME: &'static str = "STORAGE_INFORMATION";
23026 const EXTRA_CRC: u8 = 179u8;
23027 const ENCODED_LEN: usize = 61usize;
23028 fn deser(
23029 _version: MavlinkVersion,
23030 __input: &[u8],
23031 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23032 let avail_len = __input.len();
23033 let mut payload_buf = [0; Self::ENCODED_LEN];
23034 let mut buf = if avail_len < Self::ENCODED_LEN {
23035 payload_buf[0..avail_len].copy_from_slice(__input);
23036 Bytes::new(&payload_buf)
23037 } else {
23038 Bytes::new(__input)
23039 };
23040 let mut __struct = Self::default();
23041 __struct.time_boot_ms = buf.get_u32_le();
23042 __struct.total_capacity = buf.get_f32_le();
23043 __struct.used_capacity = buf.get_f32_le();
23044 __struct.available_capacity = buf.get_f32_le();
23045 __struct.read_speed = buf.get_f32_le();
23046 __struct.write_speed = buf.get_f32_le();
23047 __struct.storage_id = buf.get_u8();
23048 __struct.storage_count = buf.get_u8();
23049 let tmp = buf.get_u8();
23050 __struct.status =
23051 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23052 enum_type: "StorageStatus",
23053 value: tmp as u32,
23054 })?;
23055 let tmp = buf.get_u8();
23056 __struct.mavtype =
23057 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23058 enum_type: "StorageType",
23059 value: tmp as u32,
23060 })?;
23061 for v in &mut __struct.name {
23062 let val = buf.get_u8();
23063 *v = val;
23064 }
23065 let tmp = buf.get_u8();
23066 __struct.storage_usage = StorageUsageFlag::from_bits(tmp & StorageUsageFlag::all().bits())
23067 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
23068 flag_type: "StorageUsageFlag",
23069 value: tmp as u32,
23070 })?;
23071 Ok(__struct)
23072 }
23073 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23074 let mut __tmp = BytesMut::new(bytes);
23075 #[allow(clippy::absurd_extreme_comparisons)]
23076 #[allow(unused_comparisons)]
23077 if __tmp.remaining() < Self::ENCODED_LEN {
23078 panic!(
23079 "buffer is too small (need {} bytes, but got {})",
23080 Self::ENCODED_LEN,
23081 __tmp.remaining(),
23082 )
23083 }
23084 __tmp.put_u32_le(self.time_boot_ms);
23085 __tmp.put_f32_le(self.total_capacity);
23086 __tmp.put_f32_le(self.used_capacity);
23087 __tmp.put_f32_le(self.available_capacity);
23088 __tmp.put_f32_le(self.read_speed);
23089 __tmp.put_f32_le(self.write_speed);
23090 __tmp.put_u8(self.storage_id);
23091 __tmp.put_u8(self.storage_count);
23092 __tmp.put_u8(self.status as u8);
23093 __tmp.put_u8(self.mavtype as u8);
23094 for val in &self.name {
23095 __tmp.put_u8(*val);
23096 }
23097 __tmp.put_u8(self.storage_usage.bits());
23098 if matches!(version, MavlinkVersion::V2) {
23099 let len = __tmp.len();
23100 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23101 } else {
23102 __tmp.len()
23103 }
23104 }
23105}
23106#[doc = "id: 276"]
23107#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
23108#[derive(Debug, Clone, PartialEq)]
23109#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23110#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23111pub struct CAMERA_TRACKING_GEO_STATUS_DATA {
23112 #[doc = "Latitude of tracked object"]
23113 pub lat: i32,
23114 #[doc = "Longitude of tracked object"]
23115 pub lon: i32,
23116 #[doc = "Altitude of tracked object(AMSL, WGS84)"]
23117 pub alt: f32,
23118 #[doc = "Horizontal accuracy. NAN if unknown"]
23119 pub h_acc: f32,
23120 #[doc = "Vertical accuracy. NAN if unknown"]
23121 pub v_acc: f32,
23122 #[doc = "North velocity of tracked object. NAN if unknown"]
23123 pub vel_n: f32,
23124 #[doc = "East velocity of tracked object. NAN if unknown"]
23125 pub vel_e: f32,
23126 #[doc = "Down velocity of tracked object. NAN if unknown"]
23127 pub vel_d: f32,
23128 #[doc = "Velocity accuracy. NAN if unknown"]
23129 pub vel_acc: f32,
23130 #[doc = "Distance between camera and tracked object. NAN if unknown"]
23131 pub dist: f32,
23132 #[doc = "Heading in radians, in NED. NAN if unknown"]
23133 pub hdg: f32,
23134 #[doc = "Accuracy of heading, in NED. NAN if unknown"]
23135 pub hdg_acc: f32,
23136 #[doc = "Current tracking status"]
23137 pub tracking_status: CameraTrackingStatusFlags,
23138 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
23139 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23140 pub camera_device_id: u8,
23141}
23142impl CAMERA_TRACKING_GEO_STATUS_DATA {
23143 pub const ENCODED_LEN: usize = 50usize;
23144 pub const DEFAULT: Self = Self {
23145 lat: 0_i32,
23146 lon: 0_i32,
23147 alt: 0.0_f32,
23148 h_acc: 0.0_f32,
23149 v_acc: 0.0_f32,
23150 vel_n: 0.0_f32,
23151 vel_e: 0.0_f32,
23152 vel_d: 0.0_f32,
23153 vel_acc: 0.0_f32,
23154 dist: 0.0_f32,
23155 hdg: 0.0_f32,
23156 hdg_acc: 0.0_f32,
23157 tracking_status: CameraTrackingStatusFlags::DEFAULT,
23158 camera_device_id: 0_u8,
23159 };
23160 #[cfg(feature = "arbitrary")]
23161 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23162 use arbitrary::{Arbitrary, Unstructured};
23163 let mut buf = [0u8; 1024];
23164 rng.fill_bytes(&mut buf);
23165 let mut unstructured = Unstructured::new(&buf);
23166 Self::arbitrary(&mut unstructured).unwrap_or_default()
23167 }
23168}
23169impl Default for CAMERA_TRACKING_GEO_STATUS_DATA {
23170 fn default() -> Self {
23171 Self::DEFAULT.clone()
23172 }
23173}
23174impl MessageData for CAMERA_TRACKING_GEO_STATUS_DATA {
23175 type Message = MavMessage;
23176 const ID: u32 = 276u32;
23177 const NAME: &'static str = "CAMERA_TRACKING_GEO_STATUS";
23178 const EXTRA_CRC: u8 = 18u8;
23179 const ENCODED_LEN: usize = 50usize;
23180 fn deser(
23181 _version: MavlinkVersion,
23182 __input: &[u8],
23183 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23184 let avail_len = __input.len();
23185 let mut payload_buf = [0; Self::ENCODED_LEN];
23186 let mut buf = if avail_len < Self::ENCODED_LEN {
23187 payload_buf[0..avail_len].copy_from_slice(__input);
23188 Bytes::new(&payload_buf)
23189 } else {
23190 Bytes::new(__input)
23191 };
23192 let mut __struct = Self::default();
23193 __struct.lat = buf.get_i32_le();
23194 __struct.lon = buf.get_i32_le();
23195 __struct.alt = buf.get_f32_le();
23196 __struct.h_acc = buf.get_f32_le();
23197 __struct.v_acc = buf.get_f32_le();
23198 __struct.vel_n = buf.get_f32_le();
23199 __struct.vel_e = buf.get_f32_le();
23200 __struct.vel_d = buf.get_f32_le();
23201 __struct.vel_acc = buf.get_f32_le();
23202 __struct.dist = buf.get_f32_le();
23203 __struct.hdg = buf.get_f32_le();
23204 __struct.hdg_acc = buf.get_f32_le();
23205 let tmp = buf.get_u8();
23206 __struct.tracking_status =
23207 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23208 enum_type: "CameraTrackingStatusFlags",
23209 value: tmp as u32,
23210 })?;
23211 __struct.camera_device_id = buf.get_u8();
23212 Ok(__struct)
23213 }
23214 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23215 let mut __tmp = BytesMut::new(bytes);
23216 #[allow(clippy::absurd_extreme_comparisons)]
23217 #[allow(unused_comparisons)]
23218 if __tmp.remaining() < Self::ENCODED_LEN {
23219 panic!(
23220 "buffer is too small (need {} bytes, but got {})",
23221 Self::ENCODED_LEN,
23222 __tmp.remaining(),
23223 )
23224 }
23225 __tmp.put_i32_le(self.lat);
23226 __tmp.put_i32_le(self.lon);
23227 __tmp.put_f32_le(self.alt);
23228 __tmp.put_f32_le(self.h_acc);
23229 __tmp.put_f32_le(self.v_acc);
23230 __tmp.put_f32_le(self.vel_n);
23231 __tmp.put_f32_le(self.vel_e);
23232 __tmp.put_f32_le(self.vel_d);
23233 __tmp.put_f32_le(self.vel_acc);
23234 __tmp.put_f32_le(self.dist);
23235 __tmp.put_f32_le(self.hdg);
23236 __tmp.put_f32_le(self.hdg_acc);
23237 __tmp.put_u8(self.tracking_status as u8);
23238 __tmp.put_u8(self.camera_device_id);
23239 if matches!(version, MavlinkVersion::V2) {
23240 let len = __tmp.len();
23241 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23242 } else {
23243 __tmp.len()
23244 }
23245 }
23246}
23247#[doc = "id: 12902"]
23248#[doc = "Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes."]
23249#[derive(Debug, Clone, PartialEq)]
23250#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23251#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23252pub struct OPEN_DRONE_ID_AUTHENTICATION_DATA {
23253 #[doc = "This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
23254 pub timestamp: u32,
23255 #[doc = "System ID (0 for broadcast)."]
23256 pub target_system: u8,
23257 #[doc = "Component ID (0 for broadcast)."]
23258 pub target_component: u8,
23259 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
23260 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23261 pub id_or_mac: [u8; 20],
23262 #[doc = "Indicates the type of authentication."]
23263 pub authentication_type: MavOdidAuthType,
23264 #[doc = "Allowed range is 0 - 15."]
23265 pub data_page: u8,
23266 #[doc = "This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
23267 pub last_page_index: u8,
23268 #[doc = "This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
23269 pub length: u8,
23270 #[doc = "Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field."]
23271 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23272 pub authentication_data: [u8; 23],
23273}
23274impl OPEN_DRONE_ID_AUTHENTICATION_DATA {
23275 pub const ENCODED_LEN: usize = 53usize;
23276 pub const DEFAULT: Self = Self {
23277 timestamp: 0_u32,
23278 target_system: 0_u8,
23279 target_component: 0_u8,
23280 id_or_mac: [0_u8; 20usize],
23281 authentication_type: MavOdidAuthType::DEFAULT,
23282 data_page: 0_u8,
23283 last_page_index: 0_u8,
23284 length: 0_u8,
23285 authentication_data: [0_u8; 23usize],
23286 };
23287 #[cfg(feature = "arbitrary")]
23288 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23289 use arbitrary::{Arbitrary, Unstructured};
23290 let mut buf = [0u8; 1024];
23291 rng.fill_bytes(&mut buf);
23292 let mut unstructured = Unstructured::new(&buf);
23293 Self::arbitrary(&mut unstructured).unwrap_or_default()
23294 }
23295}
23296impl Default for OPEN_DRONE_ID_AUTHENTICATION_DATA {
23297 fn default() -> Self {
23298 Self::DEFAULT.clone()
23299 }
23300}
23301impl MessageData for OPEN_DRONE_ID_AUTHENTICATION_DATA {
23302 type Message = MavMessage;
23303 const ID: u32 = 12902u32;
23304 const NAME: &'static str = "OPEN_DRONE_ID_AUTHENTICATION";
23305 const EXTRA_CRC: u8 = 140u8;
23306 const ENCODED_LEN: usize = 53usize;
23307 fn deser(
23308 _version: MavlinkVersion,
23309 __input: &[u8],
23310 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23311 let avail_len = __input.len();
23312 let mut payload_buf = [0; Self::ENCODED_LEN];
23313 let mut buf = if avail_len < Self::ENCODED_LEN {
23314 payload_buf[0..avail_len].copy_from_slice(__input);
23315 Bytes::new(&payload_buf)
23316 } else {
23317 Bytes::new(__input)
23318 };
23319 let mut __struct = Self::default();
23320 __struct.timestamp = buf.get_u32_le();
23321 __struct.target_system = buf.get_u8();
23322 __struct.target_component = buf.get_u8();
23323 for v in &mut __struct.id_or_mac {
23324 let val = buf.get_u8();
23325 *v = val;
23326 }
23327 let tmp = buf.get_u8();
23328 __struct.authentication_type =
23329 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23330 enum_type: "MavOdidAuthType",
23331 value: tmp as u32,
23332 })?;
23333 __struct.data_page = buf.get_u8();
23334 __struct.last_page_index = buf.get_u8();
23335 __struct.length = buf.get_u8();
23336 for v in &mut __struct.authentication_data {
23337 let val = buf.get_u8();
23338 *v = val;
23339 }
23340 Ok(__struct)
23341 }
23342 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23343 let mut __tmp = BytesMut::new(bytes);
23344 #[allow(clippy::absurd_extreme_comparisons)]
23345 #[allow(unused_comparisons)]
23346 if __tmp.remaining() < Self::ENCODED_LEN {
23347 panic!(
23348 "buffer is too small (need {} bytes, but got {})",
23349 Self::ENCODED_LEN,
23350 __tmp.remaining(),
23351 )
23352 }
23353 __tmp.put_u32_le(self.timestamp);
23354 __tmp.put_u8(self.target_system);
23355 __tmp.put_u8(self.target_component);
23356 for val in &self.id_or_mac {
23357 __tmp.put_u8(*val);
23358 }
23359 __tmp.put_u8(self.authentication_type as u8);
23360 __tmp.put_u8(self.data_page);
23361 __tmp.put_u8(self.last_page_index);
23362 __tmp.put_u8(self.length);
23363 for val in &self.authentication_data {
23364 __tmp.put_u8(*val);
23365 }
23366 if matches!(version, MavlinkVersion::V2) {
23367 let len = __tmp.len();
23368 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23369 } else {
23370 __tmp.len()
23371 }
23372 }
23373}
23374#[doc = "id: 331"]
23375#[doc = "Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (<http://www.ros.org/reps/rep-0147.html>)."]
23376#[derive(Debug, Clone, PartialEq)]
23377#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23378#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23379pub struct ODOMETRY_DATA {
23380 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
23381 pub time_usec: u64,
23382 #[doc = "X Position"]
23383 pub x: f32,
23384 #[doc = "Y Position"]
23385 pub y: f32,
23386 #[doc = "Z Position"]
23387 pub z: f32,
23388 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
23389 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23390 pub q: [f32; 4],
23391 #[doc = "X linear speed"]
23392 pub vx: f32,
23393 #[doc = "Y linear speed"]
23394 pub vy: f32,
23395 #[doc = "Z linear speed"]
23396 pub vz: f32,
23397 #[doc = "Roll angular speed"]
23398 pub rollspeed: f32,
23399 #[doc = "Pitch angular speed"]
23400 pub pitchspeed: f32,
23401 #[doc = "Yaw angular speed"]
23402 pub yawspeed: f32,
23403 #[doc = "Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
23404 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23405 pub pose_covariance: [f32; 21],
23406 #[doc = "Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
23407 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23408 pub velocity_covariance: [f32; 21],
23409 #[doc = "Coordinate frame of reference for the pose data."]
23410 pub frame_id: MavFrame,
23411 #[doc = "Coordinate frame of reference for the velocity in free space (twist) data."]
23412 pub child_frame_id: MavFrame,
23413 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
23414 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23415 pub reset_counter: u8,
23416 #[doc = "Type of estimator that is providing the odometry."]
23417 #[cfg_attr(feature = "serde", serde(default))]
23418 pub estimator_type: MavEstimatorType,
23419 #[doc = "Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality"]
23420 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23421 pub quality: i8,
23422}
23423impl ODOMETRY_DATA {
23424 pub const ENCODED_LEN: usize = 233usize;
23425 pub const DEFAULT: Self = Self {
23426 time_usec: 0_u64,
23427 x: 0.0_f32,
23428 y: 0.0_f32,
23429 z: 0.0_f32,
23430 q: [0.0_f32; 4usize],
23431 vx: 0.0_f32,
23432 vy: 0.0_f32,
23433 vz: 0.0_f32,
23434 rollspeed: 0.0_f32,
23435 pitchspeed: 0.0_f32,
23436 yawspeed: 0.0_f32,
23437 pose_covariance: [0.0_f32; 21usize],
23438 velocity_covariance: [0.0_f32; 21usize],
23439 frame_id: MavFrame::DEFAULT,
23440 child_frame_id: MavFrame::DEFAULT,
23441 reset_counter: 0_u8,
23442 estimator_type: MavEstimatorType::DEFAULT,
23443 quality: 0_i8,
23444 };
23445 #[cfg(feature = "arbitrary")]
23446 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23447 use arbitrary::{Arbitrary, Unstructured};
23448 let mut buf = [0u8; 1024];
23449 rng.fill_bytes(&mut buf);
23450 let mut unstructured = Unstructured::new(&buf);
23451 Self::arbitrary(&mut unstructured).unwrap_or_default()
23452 }
23453}
23454impl Default for ODOMETRY_DATA {
23455 fn default() -> Self {
23456 Self::DEFAULT.clone()
23457 }
23458}
23459impl MessageData for ODOMETRY_DATA {
23460 type Message = MavMessage;
23461 const ID: u32 = 331u32;
23462 const NAME: &'static str = "ODOMETRY";
23463 const EXTRA_CRC: u8 = 91u8;
23464 const ENCODED_LEN: usize = 233usize;
23465 fn deser(
23466 _version: MavlinkVersion,
23467 __input: &[u8],
23468 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23469 let avail_len = __input.len();
23470 let mut payload_buf = [0; Self::ENCODED_LEN];
23471 let mut buf = if avail_len < Self::ENCODED_LEN {
23472 payload_buf[0..avail_len].copy_from_slice(__input);
23473 Bytes::new(&payload_buf)
23474 } else {
23475 Bytes::new(__input)
23476 };
23477 let mut __struct = Self::default();
23478 __struct.time_usec = buf.get_u64_le();
23479 __struct.x = buf.get_f32_le();
23480 __struct.y = buf.get_f32_le();
23481 __struct.z = buf.get_f32_le();
23482 for v in &mut __struct.q {
23483 let val = buf.get_f32_le();
23484 *v = val;
23485 }
23486 __struct.vx = buf.get_f32_le();
23487 __struct.vy = buf.get_f32_le();
23488 __struct.vz = buf.get_f32_le();
23489 __struct.rollspeed = buf.get_f32_le();
23490 __struct.pitchspeed = buf.get_f32_le();
23491 __struct.yawspeed = buf.get_f32_le();
23492 for v in &mut __struct.pose_covariance {
23493 let val = buf.get_f32_le();
23494 *v = val;
23495 }
23496 for v in &mut __struct.velocity_covariance {
23497 let val = buf.get_f32_le();
23498 *v = val;
23499 }
23500 let tmp = buf.get_u8();
23501 __struct.frame_id =
23502 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23503 enum_type: "MavFrame",
23504 value: tmp as u32,
23505 })?;
23506 let tmp = buf.get_u8();
23507 __struct.child_frame_id =
23508 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23509 enum_type: "MavFrame",
23510 value: tmp as u32,
23511 })?;
23512 __struct.reset_counter = buf.get_u8();
23513 let tmp = buf.get_u8();
23514 __struct.estimator_type =
23515 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23516 enum_type: "MavEstimatorType",
23517 value: tmp as u32,
23518 })?;
23519 __struct.quality = buf.get_i8();
23520 Ok(__struct)
23521 }
23522 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23523 let mut __tmp = BytesMut::new(bytes);
23524 #[allow(clippy::absurd_extreme_comparisons)]
23525 #[allow(unused_comparisons)]
23526 if __tmp.remaining() < Self::ENCODED_LEN {
23527 panic!(
23528 "buffer is too small (need {} bytes, but got {})",
23529 Self::ENCODED_LEN,
23530 __tmp.remaining(),
23531 )
23532 }
23533 __tmp.put_u64_le(self.time_usec);
23534 __tmp.put_f32_le(self.x);
23535 __tmp.put_f32_le(self.y);
23536 __tmp.put_f32_le(self.z);
23537 for val in &self.q {
23538 __tmp.put_f32_le(*val);
23539 }
23540 __tmp.put_f32_le(self.vx);
23541 __tmp.put_f32_le(self.vy);
23542 __tmp.put_f32_le(self.vz);
23543 __tmp.put_f32_le(self.rollspeed);
23544 __tmp.put_f32_le(self.pitchspeed);
23545 __tmp.put_f32_le(self.yawspeed);
23546 for val in &self.pose_covariance {
23547 __tmp.put_f32_le(*val);
23548 }
23549 for val in &self.velocity_covariance {
23550 __tmp.put_f32_le(*val);
23551 }
23552 __tmp.put_u8(self.frame_id as u8);
23553 __tmp.put_u8(self.child_frame_id as u8);
23554 __tmp.put_u8(self.reset_counter);
23555 __tmp.put_u8(self.estimator_type as u8);
23556 __tmp.put_i8(self.quality);
23557 if matches!(version, MavlinkVersion::V2) {
23558 let len = __tmp.len();
23559 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23560 } else {
23561 __tmp.len()
23562 }
23563 }
23564}
23565#[doc = "id: 2"]
23566#[doc = "The system time is the time of the master clock. This can be emitted by flight controllers, onboard computers, or other components in the MAVLink network. Components that are using a less reliable time source, such as a battery-backed real time clock, can choose to match their system clock to that of a SYSTEM_TYPE that indicates a more recent time. This allows more broadly accurate date stamping of logs, and so on. If precise time synchronization is needed then use TIMESYNC instead."]
23567#[derive(Debug, Clone, PartialEq)]
23568#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23569#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23570pub struct SYSTEM_TIME_DATA {
23571 #[doc = "Timestamp (UNIX epoch time)."]
23572 pub time_unix_usec: u64,
23573 #[doc = "Timestamp (time since system boot)."]
23574 pub time_boot_ms: u32,
23575}
23576impl SYSTEM_TIME_DATA {
23577 pub const ENCODED_LEN: usize = 12usize;
23578 pub const DEFAULT: Self = Self {
23579 time_unix_usec: 0_u64,
23580 time_boot_ms: 0_u32,
23581 };
23582 #[cfg(feature = "arbitrary")]
23583 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23584 use arbitrary::{Arbitrary, Unstructured};
23585 let mut buf = [0u8; 1024];
23586 rng.fill_bytes(&mut buf);
23587 let mut unstructured = Unstructured::new(&buf);
23588 Self::arbitrary(&mut unstructured).unwrap_or_default()
23589 }
23590}
23591impl Default for SYSTEM_TIME_DATA {
23592 fn default() -> Self {
23593 Self::DEFAULT.clone()
23594 }
23595}
23596impl MessageData for SYSTEM_TIME_DATA {
23597 type Message = MavMessage;
23598 const ID: u32 = 2u32;
23599 const NAME: &'static str = "SYSTEM_TIME";
23600 const EXTRA_CRC: u8 = 137u8;
23601 const ENCODED_LEN: usize = 12usize;
23602 fn deser(
23603 _version: MavlinkVersion,
23604 __input: &[u8],
23605 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23606 let avail_len = __input.len();
23607 let mut payload_buf = [0; Self::ENCODED_LEN];
23608 let mut buf = if avail_len < Self::ENCODED_LEN {
23609 payload_buf[0..avail_len].copy_from_slice(__input);
23610 Bytes::new(&payload_buf)
23611 } else {
23612 Bytes::new(__input)
23613 };
23614 let mut __struct = Self::default();
23615 __struct.time_unix_usec = buf.get_u64_le();
23616 __struct.time_boot_ms = buf.get_u32_le();
23617 Ok(__struct)
23618 }
23619 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23620 let mut __tmp = BytesMut::new(bytes);
23621 #[allow(clippy::absurd_extreme_comparisons)]
23622 #[allow(unused_comparisons)]
23623 if __tmp.remaining() < Self::ENCODED_LEN {
23624 panic!(
23625 "buffer is too small (need {} bytes, but got {})",
23626 Self::ENCODED_LEN,
23627 __tmp.remaining(),
23628 )
23629 }
23630 __tmp.put_u64_le(self.time_unix_usec);
23631 __tmp.put_u32_le(self.time_boot_ms);
23632 if matches!(version, MavlinkVersion::V2) {
23633 let len = __tmp.len();
23634 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23635 } else {
23636 __tmp.len()
23637 }
23638 }
23639}
23640#[doc = "id: 104"]
23641#[doc = "Global position estimate from a Vicon motion system source."]
23642#[derive(Debug, Clone, PartialEq)]
23643#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23644#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23645pub struct VICON_POSITION_ESTIMATE_DATA {
23646 #[doc = "Timestamp (UNIX time or time since system boot)"]
23647 pub usec: u64,
23648 #[doc = "Global X position"]
23649 pub x: f32,
23650 #[doc = "Global Y position"]
23651 pub y: f32,
23652 #[doc = "Global Z position"]
23653 pub z: f32,
23654 #[doc = "Roll angle"]
23655 pub roll: f32,
23656 #[doc = "Pitch angle"]
23657 pub pitch: f32,
23658 #[doc = "Yaw angle"]
23659 pub yaw: f32,
23660 #[doc = "Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
23661 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23662 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23663 pub covariance: [f32; 21],
23664}
23665impl VICON_POSITION_ESTIMATE_DATA {
23666 pub const ENCODED_LEN: usize = 116usize;
23667 pub const DEFAULT: Self = Self {
23668 usec: 0_u64,
23669 x: 0.0_f32,
23670 y: 0.0_f32,
23671 z: 0.0_f32,
23672 roll: 0.0_f32,
23673 pitch: 0.0_f32,
23674 yaw: 0.0_f32,
23675 covariance: [0.0_f32; 21usize],
23676 };
23677 #[cfg(feature = "arbitrary")]
23678 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23679 use arbitrary::{Arbitrary, Unstructured};
23680 let mut buf = [0u8; 1024];
23681 rng.fill_bytes(&mut buf);
23682 let mut unstructured = Unstructured::new(&buf);
23683 Self::arbitrary(&mut unstructured).unwrap_or_default()
23684 }
23685}
23686impl Default for VICON_POSITION_ESTIMATE_DATA {
23687 fn default() -> Self {
23688 Self::DEFAULT.clone()
23689 }
23690}
23691impl MessageData for VICON_POSITION_ESTIMATE_DATA {
23692 type Message = MavMessage;
23693 const ID: u32 = 104u32;
23694 const NAME: &'static str = "VICON_POSITION_ESTIMATE";
23695 const EXTRA_CRC: u8 = 56u8;
23696 const ENCODED_LEN: usize = 116usize;
23697 fn deser(
23698 _version: MavlinkVersion,
23699 __input: &[u8],
23700 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23701 let avail_len = __input.len();
23702 let mut payload_buf = [0; Self::ENCODED_LEN];
23703 let mut buf = if avail_len < Self::ENCODED_LEN {
23704 payload_buf[0..avail_len].copy_from_slice(__input);
23705 Bytes::new(&payload_buf)
23706 } else {
23707 Bytes::new(__input)
23708 };
23709 let mut __struct = Self::default();
23710 __struct.usec = buf.get_u64_le();
23711 __struct.x = buf.get_f32_le();
23712 __struct.y = buf.get_f32_le();
23713 __struct.z = buf.get_f32_le();
23714 __struct.roll = buf.get_f32_le();
23715 __struct.pitch = buf.get_f32_le();
23716 __struct.yaw = buf.get_f32_le();
23717 for v in &mut __struct.covariance {
23718 let val = buf.get_f32_le();
23719 *v = val;
23720 }
23721 Ok(__struct)
23722 }
23723 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23724 let mut __tmp = BytesMut::new(bytes);
23725 #[allow(clippy::absurd_extreme_comparisons)]
23726 #[allow(unused_comparisons)]
23727 if __tmp.remaining() < Self::ENCODED_LEN {
23728 panic!(
23729 "buffer is too small (need {} bytes, but got {})",
23730 Self::ENCODED_LEN,
23731 __tmp.remaining(),
23732 )
23733 }
23734 __tmp.put_u64_le(self.usec);
23735 __tmp.put_f32_le(self.x);
23736 __tmp.put_f32_le(self.y);
23737 __tmp.put_f32_le(self.z);
23738 __tmp.put_f32_le(self.roll);
23739 __tmp.put_f32_le(self.pitch);
23740 __tmp.put_f32_le(self.yaw);
23741 for val in &self.covariance {
23742 __tmp.put_f32_le(*val);
23743 }
23744 if matches!(version, MavlinkVersion::V2) {
23745 let len = __tmp.len();
23746 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23747 } else {
23748 __tmp.len()
23749 }
23750 }
23751}
23752#[doc = "id: 388"]
23753#[doc = "Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages."]
23754#[derive(Debug, Clone, PartialEq)]
23755#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23756#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23757pub struct CAN_FILTER_MODIFY_DATA {
23758 #[doc = "filter IDs, length num_ids"]
23759 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23760 pub ids: [u16; 16],
23761 #[doc = "System ID."]
23762 pub target_system: u8,
23763 #[doc = "Component ID."]
23764 pub target_component: u8,
23765 #[doc = "bus number"]
23766 pub bus: u8,
23767 #[doc = "what operation to perform on the filter list. See CAN_FILTER_OP enum."]
23768 pub operation: CanFilterOp,
23769 #[doc = "number of IDs in filter list"]
23770 pub num_ids: u8,
23771}
23772impl CAN_FILTER_MODIFY_DATA {
23773 pub const ENCODED_LEN: usize = 37usize;
23774 pub const DEFAULT: Self = Self {
23775 ids: [0_u16; 16usize],
23776 target_system: 0_u8,
23777 target_component: 0_u8,
23778 bus: 0_u8,
23779 operation: CanFilterOp::DEFAULT,
23780 num_ids: 0_u8,
23781 };
23782 #[cfg(feature = "arbitrary")]
23783 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23784 use arbitrary::{Arbitrary, Unstructured};
23785 let mut buf = [0u8; 1024];
23786 rng.fill_bytes(&mut buf);
23787 let mut unstructured = Unstructured::new(&buf);
23788 Self::arbitrary(&mut unstructured).unwrap_or_default()
23789 }
23790}
23791impl Default for CAN_FILTER_MODIFY_DATA {
23792 fn default() -> Self {
23793 Self::DEFAULT.clone()
23794 }
23795}
23796impl MessageData for CAN_FILTER_MODIFY_DATA {
23797 type Message = MavMessage;
23798 const ID: u32 = 388u32;
23799 const NAME: &'static str = "CAN_FILTER_MODIFY";
23800 const EXTRA_CRC: u8 = 8u8;
23801 const ENCODED_LEN: usize = 37usize;
23802 fn deser(
23803 _version: MavlinkVersion,
23804 __input: &[u8],
23805 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23806 let avail_len = __input.len();
23807 let mut payload_buf = [0; Self::ENCODED_LEN];
23808 let mut buf = if avail_len < Self::ENCODED_LEN {
23809 payload_buf[0..avail_len].copy_from_slice(__input);
23810 Bytes::new(&payload_buf)
23811 } else {
23812 Bytes::new(__input)
23813 };
23814 let mut __struct = Self::default();
23815 for v in &mut __struct.ids {
23816 let val = buf.get_u16_le();
23817 *v = val;
23818 }
23819 __struct.target_system = buf.get_u8();
23820 __struct.target_component = buf.get_u8();
23821 __struct.bus = buf.get_u8();
23822 let tmp = buf.get_u8();
23823 __struct.operation =
23824 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23825 enum_type: "CanFilterOp",
23826 value: tmp as u32,
23827 })?;
23828 __struct.num_ids = buf.get_u8();
23829 Ok(__struct)
23830 }
23831 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23832 let mut __tmp = BytesMut::new(bytes);
23833 #[allow(clippy::absurd_extreme_comparisons)]
23834 #[allow(unused_comparisons)]
23835 if __tmp.remaining() < Self::ENCODED_LEN {
23836 panic!(
23837 "buffer is too small (need {} bytes, but got {})",
23838 Self::ENCODED_LEN,
23839 __tmp.remaining(),
23840 )
23841 }
23842 for val in &self.ids {
23843 __tmp.put_u16_le(*val);
23844 }
23845 __tmp.put_u8(self.target_system);
23846 __tmp.put_u8(self.target_component);
23847 __tmp.put_u8(self.bus);
23848 __tmp.put_u8(self.operation as u8);
23849 __tmp.put_u8(self.num_ids);
23850 if matches!(version, MavlinkVersion::V2) {
23851 let len = __tmp.len();
23852 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23853 } else {
23854 __tmp.len()
23855 }
23856 }
23857}
23858#[doc = "id: 106"]
23859#[doc = "Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)."]
23860#[derive(Debug, Clone, PartialEq)]
23861#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23862#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23863pub struct OPTICAL_FLOW_RAD_DATA {
23864 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
23865 pub time_usec: u64,
23866 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
23867 pub integration_time_us: u32,
23868 #[doc = "Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
23869 pub integrated_x: f32,
23870 #[doc = "Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
23871 pub integrated_y: f32,
23872 #[doc = "RH rotation around X axis"]
23873 pub integrated_xgyro: f32,
23874 #[doc = "RH rotation around Y axis"]
23875 pub integrated_ygyro: f32,
23876 #[doc = "RH rotation around Z axis"]
23877 pub integrated_zgyro: f32,
23878 #[doc = "Time since the distance was sampled."]
23879 pub time_delta_distance_us: u32,
23880 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
23881 pub distance: f32,
23882 #[doc = "Temperature"]
23883 pub temperature: i16,
23884 #[doc = "Sensor ID"]
23885 pub sensor_id: u8,
23886 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
23887 pub quality: u8,
23888}
23889impl OPTICAL_FLOW_RAD_DATA {
23890 pub const ENCODED_LEN: usize = 44usize;
23891 pub const DEFAULT: Self = Self {
23892 time_usec: 0_u64,
23893 integration_time_us: 0_u32,
23894 integrated_x: 0.0_f32,
23895 integrated_y: 0.0_f32,
23896 integrated_xgyro: 0.0_f32,
23897 integrated_ygyro: 0.0_f32,
23898 integrated_zgyro: 0.0_f32,
23899 time_delta_distance_us: 0_u32,
23900 distance: 0.0_f32,
23901 temperature: 0_i16,
23902 sensor_id: 0_u8,
23903 quality: 0_u8,
23904 };
23905 #[cfg(feature = "arbitrary")]
23906 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23907 use arbitrary::{Arbitrary, Unstructured};
23908 let mut buf = [0u8; 1024];
23909 rng.fill_bytes(&mut buf);
23910 let mut unstructured = Unstructured::new(&buf);
23911 Self::arbitrary(&mut unstructured).unwrap_or_default()
23912 }
23913}
23914impl Default for OPTICAL_FLOW_RAD_DATA {
23915 fn default() -> Self {
23916 Self::DEFAULT.clone()
23917 }
23918}
23919impl MessageData for OPTICAL_FLOW_RAD_DATA {
23920 type Message = MavMessage;
23921 const ID: u32 = 106u32;
23922 const NAME: &'static str = "OPTICAL_FLOW_RAD";
23923 const EXTRA_CRC: u8 = 138u8;
23924 const ENCODED_LEN: usize = 44usize;
23925 fn deser(
23926 _version: MavlinkVersion,
23927 __input: &[u8],
23928 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23929 let avail_len = __input.len();
23930 let mut payload_buf = [0; Self::ENCODED_LEN];
23931 let mut buf = if avail_len < Self::ENCODED_LEN {
23932 payload_buf[0..avail_len].copy_from_slice(__input);
23933 Bytes::new(&payload_buf)
23934 } else {
23935 Bytes::new(__input)
23936 };
23937 let mut __struct = Self::default();
23938 __struct.time_usec = buf.get_u64_le();
23939 __struct.integration_time_us = buf.get_u32_le();
23940 __struct.integrated_x = buf.get_f32_le();
23941 __struct.integrated_y = buf.get_f32_le();
23942 __struct.integrated_xgyro = buf.get_f32_le();
23943 __struct.integrated_ygyro = buf.get_f32_le();
23944 __struct.integrated_zgyro = buf.get_f32_le();
23945 __struct.time_delta_distance_us = buf.get_u32_le();
23946 __struct.distance = buf.get_f32_le();
23947 __struct.temperature = buf.get_i16_le();
23948 __struct.sensor_id = buf.get_u8();
23949 __struct.quality = buf.get_u8();
23950 Ok(__struct)
23951 }
23952 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23953 let mut __tmp = BytesMut::new(bytes);
23954 #[allow(clippy::absurd_extreme_comparisons)]
23955 #[allow(unused_comparisons)]
23956 if __tmp.remaining() < Self::ENCODED_LEN {
23957 panic!(
23958 "buffer is too small (need {} bytes, but got {})",
23959 Self::ENCODED_LEN,
23960 __tmp.remaining(),
23961 )
23962 }
23963 __tmp.put_u64_le(self.time_usec);
23964 __tmp.put_u32_le(self.integration_time_us);
23965 __tmp.put_f32_le(self.integrated_x);
23966 __tmp.put_f32_le(self.integrated_y);
23967 __tmp.put_f32_le(self.integrated_xgyro);
23968 __tmp.put_f32_le(self.integrated_ygyro);
23969 __tmp.put_f32_le(self.integrated_zgyro);
23970 __tmp.put_u32_le(self.time_delta_distance_us);
23971 __tmp.put_f32_le(self.distance);
23972 __tmp.put_i16_le(self.temperature);
23973 __tmp.put_u8(self.sensor_id);
23974 __tmp.put_u8(self.quality);
23975 if matches!(version, MavlinkVersion::V2) {
23976 let len = __tmp.len();
23977 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23978 } else {
23979 __tmp.len()
23980 }
23981 }
23982}
23983#[doc = "id: 370"]
23984#[doc = "Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for the frequent battery updates."]
23985#[derive(Debug, Clone, PartialEq)]
23986#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23987#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23988pub struct SMART_BATTERY_INFO_DATA {
23989 #[doc = "Capacity when full according to manufacturer, -1: field not provided."]
23990 pub capacity_full_specification: i32,
23991 #[doc = "Capacity when full (accounting for battery degradation), -1: field not provided."]
23992 pub capacity_full: i32,
23993 #[doc = "Charge/discharge cycle count. UINT16_MAX: field not provided."]
23994 pub cycle_count: u16,
23995 #[doc = "Battery weight. 0: field not provided."]
23996 pub weight: u16,
23997 #[doc = "Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value."]
23998 pub discharge_minimum_voltage: u16,
23999 #[doc = "Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value."]
24000 pub charging_minimum_voltage: u16,
24001 #[doc = "Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value."]
24002 pub resting_minimum_voltage: u16,
24003 #[doc = "Battery ID"]
24004 pub id: u8,
24005 #[doc = "Function of the battery"]
24006 pub battery_function: MavBatteryFunction,
24007 #[doc = "Type (chemistry) of the battery"]
24008 pub mavtype: MavBatteryType,
24009 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
24010 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24011 pub serial_number: [u8; 16],
24012 #[doc = "Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore."]
24013 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24014 pub device_name: [u8; 50],
24015 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
24016 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24017 pub charging_maximum_voltage: u16,
24018 #[doc = "Number of battery cells in series. 0: field not provided."]
24019 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24020 pub cells_in_series: u8,
24021 #[doc = "Maximum pack discharge current. 0: field not provided."]
24022 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24023 pub discharge_maximum_current: u32,
24024 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
24025 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24026 pub discharge_maximum_burst_current: u32,
24027 #[doc = "Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
24028 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24029 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24030 pub manufacture_date: [u8; 11],
24031}
24032impl SMART_BATTERY_INFO_DATA {
24033 pub const ENCODED_LEN: usize = 109usize;
24034 pub const DEFAULT: Self = Self {
24035 capacity_full_specification: 0_i32,
24036 capacity_full: 0_i32,
24037 cycle_count: 0_u16,
24038 weight: 0_u16,
24039 discharge_minimum_voltage: 0_u16,
24040 charging_minimum_voltage: 0_u16,
24041 resting_minimum_voltage: 0_u16,
24042 id: 0_u8,
24043 battery_function: MavBatteryFunction::DEFAULT,
24044 mavtype: MavBatteryType::DEFAULT,
24045 serial_number: [0_u8; 16usize],
24046 device_name: [0_u8; 50usize],
24047 charging_maximum_voltage: 0_u16,
24048 cells_in_series: 0_u8,
24049 discharge_maximum_current: 0_u32,
24050 discharge_maximum_burst_current: 0_u32,
24051 manufacture_date: [0_u8; 11usize],
24052 };
24053 #[cfg(feature = "arbitrary")]
24054 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24055 use arbitrary::{Arbitrary, Unstructured};
24056 let mut buf = [0u8; 1024];
24057 rng.fill_bytes(&mut buf);
24058 let mut unstructured = Unstructured::new(&buf);
24059 Self::arbitrary(&mut unstructured).unwrap_or_default()
24060 }
24061}
24062impl Default for SMART_BATTERY_INFO_DATA {
24063 fn default() -> Self {
24064 Self::DEFAULT.clone()
24065 }
24066}
24067impl MessageData for SMART_BATTERY_INFO_DATA {
24068 type Message = MavMessage;
24069 const ID: u32 = 370u32;
24070 const NAME: &'static str = "SMART_BATTERY_INFO";
24071 const EXTRA_CRC: u8 = 75u8;
24072 const ENCODED_LEN: usize = 109usize;
24073 fn deser(
24074 _version: MavlinkVersion,
24075 __input: &[u8],
24076 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24077 let avail_len = __input.len();
24078 let mut payload_buf = [0; Self::ENCODED_LEN];
24079 let mut buf = if avail_len < Self::ENCODED_LEN {
24080 payload_buf[0..avail_len].copy_from_slice(__input);
24081 Bytes::new(&payload_buf)
24082 } else {
24083 Bytes::new(__input)
24084 };
24085 let mut __struct = Self::default();
24086 __struct.capacity_full_specification = buf.get_i32_le();
24087 __struct.capacity_full = buf.get_i32_le();
24088 __struct.cycle_count = buf.get_u16_le();
24089 __struct.weight = buf.get_u16_le();
24090 __struct.discharge_minimum_voltage = buf.get_u16_le();
24091 __struct.charging_minimum_voltage = buf.get_u16_le();
24092 __struct.resting_minimum_voltage = buf.get_u16_le();
24093 __struct.id = buf.get_u8();
24094 let tmp = buf.get_u8();
24095 __struct.battery_function =
24096 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24097 enum_type: "MavBatteryFunction",
24098 value: tmp as u32,
24099 })?;
24100 let tmp = buf.get_u8();
24101 __struct.mavtype =
24102 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24103 enum_type: "MavBatteryType",
24104 value: tmp as u32,
24105 })?;
24106 for v in &mut __struct.serial_number {
24107 let val = buf.get_u8();
24108 *v = val;
24109 }
24110 for v in &mut __struct.device_name {
24111 let val = buf.get_u8();
24112 *v = val;
24113 }
24114 __struct.charging_maximum_voltage = buf.get_u16_le();
24115 __struct.cells_in_series = buf.get_u8();
24116 __struct.discharge_maximum_current = buf.get_u32_le();
24117 __struct.discharge_maximum_burst_current = buf.get_u32_le();
24118 for v in &mut __struct.manufacture_date {
24119 let val = buf.get_u8();
24120 *v = val;
24121 }
24122 Ok(__struct)
24123 }
24124 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24125 let mut __tmp = BytesMut::new(bytes);
24126 #[allow(clippy::absurd_extreme_comparisons)]
24127 #[allow(unused_comparisons)]
24128 if __tmp.remaining() < Self::ENCODED_LEN {
24129 panic!(
24130 "buffer is too small (need {} bytes, but got {})",
24131 Self::ENCODED_LEN,
24132 __tmp.remaining(),
24133 )
24134 }
24135 __tmp.put_i32_le(self.capacity_full_specification);
24136 __tmp.put_i32_le(self.capacity_full);
24137 __tmp.put_u16_le(self.cycle_count);
24138 __tmp.put_u16_le(self.weight);
24139 __tmp.put_u16_le(self.discharge_minimum_voltage);
24140 __tmp.put_u16_le(self.charging_minimum_voltage);
24141 __tmp.put_u16_le(self.resting_minimum_voltage);
24142 __tmp.put_u8(self.id);
24143 __tmp.put_u8(self.battery_function as u8);
24144 __tmp.put_u8(self.mavtype as u8);
24145 for val in &self.serial_number {
24146 __tmp.put_u8(*val);
24147 }
24148 for val in &self.device_name {
24149 __tmp.put_u8(*val);
24150 }
24151 __tmp.put_u16_le(self.charging_maximum_voltage);
24152 __tmp.put_u8(self.cells_in_series);
24153 __tmp.put_u32_le(self.discharge_maximum_current);
24154 __tmp.put_u32_le(self.discharge_maximum_burst_current);
24155 for val in &self.manufacture_date {
24156 __tmp.put_u8(*val);
24157 }
24158 if matches!(version, MavlinkVersion::V2) {
24159 let len = __tmp.len();
24160 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24161 } else {
24162 __tmp.len()
24163 }
24164 }
24165}
24166#[doc = "id: 21"]
24167#[doc = "Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
24168#[derive(Debug, Clone, PartialEq)]
24169#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24170#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24171pub struct PARAM_REQUEST_LIST_DATA {
24172 #[doc = "System ID"]
24173 pub target_system: u8,
24174 #[doc = "Component ID"]
24175 pub target_component: u8,
24176}
24177impl PARAM_REQUEST_LIST_DATA {
24178 pub const ENCODED_LEN: usize = 2usize;
24179 pub const DEFAULT: Self = Self {
24180 target_system: 0_u8,
24181 target_component: 0_u8,
24182 };
24183 #[cfg(feature = "arbitrary")]
24184 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24185 use arbitrary::{Arbitrary, Unstructured};
24186 let mut buf = [0u8; 1024];
24187 rng.fill_bytes(&mut buf);
24188 let mut unstructured = Unstructured::new(&buf);
24189 Self::arbitrary(&mut unstructured).unwrap_or_default()
24190 }
24191}
24192impl Default for PARAM_REQUEST_LIST_DATA {
24193 fn default() -> Self {
24194 Self::DEFAULT.clone()
24195 }
24196}
24197impl MessageData for PARAM_REQUEST_LIST_DATA {
24198 type Message = MavMessage;
24199 const ID: u32 = 21u32;
24200 const NAME: &'static str = "PARAM_REQUEST_LIST";
24201 const EXTRA_CRC: u8 = 159u8;
24202 const ENCODED_LEN: usize = 2usize;
24203 fn deser(
24204 _version: MavlinkVersion,
24205 __input: &[u8],
24206 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24207 let avail_len = __input.len();
24208 let mut payload_buf = [0; Self::ENCODED_LEN];
24209 let mut buf = if avail_len < Self::ENCODED_LEN {
24210 payload_buf[0..avail_len].copy_from_slice(__input);
24211 Bytes::new(&payload_buf)
24212 } else {
24213 Bytes::new(__input)
24214 };
24215 let mut __struct = Self::default();
24216 __struct.target_system = buf.get_u8();
24217 __struct.target_component = buf.get_u8();
24218 Ok(__struct)
24219 }
24220 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24221 let mut __tmp = BytesMut::new(bytes);
24222 #[allow(clippy::absurd_extreme_comparisons)]
24223 #[allow(unused_comparisons)]
24224 if __tmp.remaining() < Self::ENCODED_LEN {
24225 panic!(
24226 "buffer is too small (need {} bytes, but got {})",
24227 Self::ENCODED_LEN,
24228 __tmp.remaining(),
24229 )
24230 }
24231 __tmp.put_u8(self.target_system);
24232 __tmp.put_u8(self.target_component);
24233 if matches!(version, MavlinkVersion::V2) {
24234 let len = __tmp.len();
24235 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24236 } else {
24237 __tmp.len()
24238 }
24239 }
24240}
24241#[doc = "id: 8"]
24242#[doc = "Status generated in each node in the communication chain and injected into MAVLink stream."]
24243#[derive(Debug, Clone, PartialEq)]
24244#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24245#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24246pub struct LINK_NODE_STATUS_DATA {
24247 #[doc = "Timestamp (time since system boot)."]
24248 pub timestamp: u64,
24249 #[doc = "Transmit rate"]
24250 pub tx_rate: u32,
24251 #[doc = "Receive rate"]
24252 pub rx_rate: u32,
24253 #[doc = "Messages sent"]
24254 pub messages_sent: u32,
24255 #[doc = "Messages received (estimated from counting seq)"]
24256 pub messages_received: u32,
24257 #[doc = "Messages lost (estimated from counting seq)"]
24258 pub messages_lost: u32,
24259 #[doc = "Number of bytes that could not be parsed correctly."]
24260 pub rx_parse_err: u16,
24261 #[doc = "Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX"]
24262 pub tx_overflows: u16,
24263 #[doc = "Receive buffer overflows. This number wraps around as it reaches UINT16_MAX"]
24264 pub rx_overflows: u16,
24265 #[doc = "Remaining free transmit buffer space"]
24266 pub tx_buf: u8,
24267 #[doc = "Remaining free receive buffer space"]
24268 pub rx_buf: u8,
24269}
24270impl LINK_NODE_STATUS_DATA {
24271 pub const ENCODED_LEN: usize = 36usize;
24272 pub const DEFAULT: Self = Self {
24273 timestamp: 0_u64,
24274 tx_rate: 0_u32,
24275 rx_rate: 0_u32,
24276 messages_sent: 0_u32,
24277 messages_received: 0_u32,
24278 messages_lost: 0_u32,
24279 rx_parse_err: 0_u16,
24280 tx_overflows: 0_u16,
24281 rx_overflows: 0_u16,
24282 tx_buf: 0_u8,
24283 rx_buf: 0_u8,
24284 };
24285 #[cfg(feature = "arbitrary")]
24286 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24287 use arbitrary::{Arbitrary, Unstructured};
24288 let mut buf = [0u8; 1024];
24289 rng.fill_bytes(&mut buf);
24290 let mut unstructured = Unstructured::new(&buf);
24291 Self::arbitrary(&mut unstructured).unwrap_or_default()
24292 }
24293}
24294impl Default for LINK_NODE_STATUS_DATA {
24295 fn default() -> Self {
24296 Self::DEFAULT.clone()
24297 }
24298}
24299impl MessageData for LINK_NODE_STATUS_DATA {
24300 type Message = MavMessage;
24301 const ID: u32 = 8u32;
24302 const NAME: &'static str = "LINK_NODE_STATUS";
24303 const EXTRA_CRC: u8 = 117u8;
24304 const ENCODED_LEN: usize = 36usize;
24305 fn deser(
24306 _version: MavlinkVersion,
24307 __input: &[u8],
24308 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24309 let avail_len = __input.len();
24310 let mut payload_buf = [0; Self::ENCODED_LEN];
24311 let mut buf = if avail_len < Self::ENCODED_LEN {
24312 payload_buf[0..avail_len].copy_from_slice(__input);
24313 Bytes::new(&payload_buf)
24314 } else {
24315 Bytes::new(__input)
24316 };
24317 let mut __struct = Self::default();
24318 __struct.timestamp = buf.get_u64_le();
24319 __struct.tx_rate = buf.get_u32_le();
24320 __struct.rx_rate = buf.get_u32_le();
24321 __struct.messages_sent = buf.get_u32_le();
24322 __struct.messages_received = buf.get_u32_le();
24323 __struct.messages_lost = buf.get_u32_le();
24324 __struct.rx_parse_err = buf.get_u16_le();
24325 __struct.tx_overflows = buf.get_u16_le();
24326 __struct.rx_overflows = buf.get_u16_le();
24327 __struct.tx_buf = buf.get_u8();
24328 __struct.rx_buf = buf.get_u8();
24329 Ok(__struct)
24330 }
24331 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24332 let mut __tmp = BytesMut::new(bytes);
24333 #[allow(clippy::absurd_extreme_comparisons)]
24334 #[allow(unused_comparisons)]
24335 if __tmp.remaining() < Self::ENCODED_LEN {
24336 panic!(
24337 "buffer is too small (need {} bytes, but got {})",
24338 Self::ENCODED_LEN,
24339 __tmp.remaining(),
24340 )
24341 }
24342 __tmp.put_u64_le(self.timestamp);
24343 __tmp.put_u32_le(self.tx_rate);
24344 __tmp.put_u32_le(self.rx_rate);
24345 __tmp.put_u32_le(self.messages_sent);
24346 __tmp.put_u32_le(self.messages_received);
24347 __tmp.put_u32_le(self.messages_lost);
24348 __tmp.put_u16_le(self.rx_parse_err);
24349 __tmp.put_u16_le(self.tx_overflows);
24350 __tmp.put_u16_le(self.rx_overflows);
24351 __tmp.put_u8(self.tx_buf);
24352 __tmp.put_u8(self.rx_buf);
24353 if matches!(version, MavlinkVersion::V2) {
24354 let len = __tmp.len();
24355 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24356 } else {
24357 __tmp.len()
24358 }
24359 }
24360}
24361#[doc = "id: 12905"]
24362#[doc = "Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID."]
24363#[derive(Debug, Clone, PartialEq)]
24364#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24365#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24366pub struct OPEN_DRONE_ID_OPERATOR_ID_DATA {
24367 #[doc = "System ID (0 for broadcast)."]
24368 pub target_system: u8,
24369 #[doc = "Component ID (0 for broadcast)."]
24370 pub target_component: u8,
24371 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
24372 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24373 pub id_or_mac: [u8; 20],
24374 #[doc = "Indicates the type of the operator_id field."]
24375 pub operator_id_type: MavOdidOperatorIdType,
24376 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
24377 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24378 pub operator_id: [u8; 20],
24379}
24380impl OPEN_DRONE_ID_OPERATOR_ID_DATA {
24381 pub const ENCODED_LEN: usize = 43usize;
24382 pub const DEFAULT: Self = Self {
24383 target_system: 0_u8,
24384 target_component: 0_u8,
24385 id_or_mac: [0_u8; 20usize],
24386 operator_id_type: MavOdidOperatorIdType::DEFAULT,
24387 operator_id: [0_u8; 20usize],
24388 };
24389 #[cfg(feature = "arbitrary")]
24390 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24391 use arbitrary::{Arbitrary, Unstructured};
24392 let mut buf = [0u8; 1024];
24393 rng.fill_bytes(&mut buf);
24394 let mut unstructured = Unstructured::new(&buf);
24395 Self::arbitrary(&mut unstructured).unwrap_or_default()
24396 }
24397}
24398impl Default for OPEN_DRONE_ID_OPERATOR_ID_DATA {
24399 fn default() -> Self {
24400 Self::DEFAULT.clone()
24401 }
24402}
24403impl MessageData for OPEN_DRONE_ID_OPERATOR_ID_DATA {
24404 type Message = MavMessage;
24405 const ID: u32 = 12905u32;
24406 const NAME: &'static str = "OPEN_DRONE_ID_OPERATOR_ID";
24407 const EXTRA_CRC: u8 = 49u8;
24408 const ENCODED_LEN: usize = 43usize;
24409 fn deser(
24410 _version: MavlinkVersion,
24411 __input: &[u8],
24412 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24413 let avail_len = __input.len();
24414 let mut payload_buf = [0; Self::ENCODED_LEN];
24415 let mut buf = if avail_len < Self::ENCODED_LEN {
24416 payload_buf[0..avail_len].copy_from_slice(__input);
24417 Bytes::new(&payload_buf)
24418 } else {
24419 Bytes::new(__input)
24420 };
24421 let mut __struct = Self::default();
24422 __struct.target_system = buf.get_u8();
24423 __struct.target_component = buf.get_u8();
24424 for v in &mut __struct.id_or_mac {
24425 let val = buf.get_u8();
24426 *v = val;
24427 }
24428 let tmp = buf.get_u8();
24429 __struct.operator_id_type =
24430 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24431 enum_type: "MavOdidOperatorIdType",
24432 value: tmp as u32,
24433 })?;
24434 for v in &mut __struct.operator_id {
24435 let val = buf.get_u8();
24436 *v = val;
24437 }
24438 Ok(__struct)
24439 }
24440 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24441 let mut __tmp = BytesMut::new(bytes);
24442 #[allow(clippy::absurd_extreme_comparisons)]
24443 #[allow(unused_comparisons)]
24444 if __tmp.remaining() < Self::ENCODED_LEN {
24445 panic!(
24446 "buffer is too small (need {} bytes, but got {})",
24447 Self::ENCODED_LEN,
24448 __tmp.remaining(),
24449 )
24450 }
24451 __tmp.put_u8(self.target_system);
24452 __tmp.put_u8(self.target_component);
24453 for val in &self.id_or_mac {
24454 __tmp.put_u8(*val);
24455 }
24456 __tmp.put_u8(self.operator_id_type as u8);
24457 for val in &self.operator_id {
24458 __tmp.put_u8(*val);
24459 }
24460 if matches!(version, MavlinkVersion::V2) {
24461 let len = __tmp.len();
24462 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24463 } else {
24464 __tmp.len()
24465 }
24466 }
24467}
24468#[doc = "id: 252"]
24469#[doc = "Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
24470#[derive(Debug, Clone, PartialEq)]
24471#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24472#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24473pub struct NAMED_VALUE_INT_DATA {
24474 #[doc = "Timestamp (time since system boot)."]
24475 pub time_boot_ms: u32,
24476 #[doc = "Signed integer value"]
24477 pub value: i32,
24478 #[doc = "Name of the debug variable"]
24479 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24480 pub name: [u8; 10],
24481}
24482impl NAMED_VALUE_INT_DATA {
24483 pub const ENCODED_LEN: usize = 18usize;
24484 pub const DEFAULT: Self = Self {
24485 time_boot_ms: 0_u32,
24486 value: 0_i32,
24487 name: [0_u8; 10usize],
24488 };
24489 #[cfg(feature = "arbitrary")]
24490 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24491 use arbitrary::{Arbitrary, Unstructured};
24492 let mut buf = [0u8; 1024];
24493 rng.fill_bytes(&mut buf);
24494 let mut unstructured = Unstructured::new(&buf);
24495 Self::arbitrary(&mut unstructured).unwrap_or_default()
24496 }
24497}
24498impl Default for NAMED_VALUE_INT_DATA {
24499 fn default() -> Self {
24500 Self::DEFAULT.clone()
24501 }
24502}
24503impl MessageData for NAMED_VALUE_INT_DATA {
24504 type Message = MavMessage;
24505 const ID: u32 = 252u32;
24506 const NAME: &'static str = "NAMED_VALUE_INT";
24507 const EXTRA_CRC: u8 = 44u8;
24508 const ENCODED_LEN: usize = 18usize;
24509 fn deser(
24510 _version: MavlinkVersion,
24511 __input: &[u8],
24512 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24513 let avail_len = __input.len();
24514 let mut payload_buf = [0; Self::ENCODED_LEN];
24515 let mut buf = if avail_len < Self::ENCODED_LEN {
24516 payload_buf[0..avail_len].copy_from_slice(__input);
24517 Bytes::new(&payload_buf)
24518 } else {
24519 Bytes::new(__input)
24520 };
24521 let mut __struct = Self::default();
24522 __struct.time_boot_ms = buf.get_u32_le();
24523 __struct.value = buf.get_i32_le();
24524 for v in &mut __struct.name {
24525 let val = buf.get_u8();
24526 *v = val;
24527 }
24528 Ok(__struct)
24529 }
24530 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24531 let mut __tmp = BytesMut::new(bytes);
24532 #[allow(clippy::absurd_extreme_comparisons)]
24533 #[allow(unused_comparisons)]
24534 if __tmp.remaining() < Self::ENCODED_LEN {
24535 panic!(
24536 "buffer is too small (need {} bytes, but got {})",
24537 Self::ENCODED_LEN,
24538 __tmp.remaining(),
24539 )
24540 }
24541 __tmp.put_u32_le(self.time_boot_ms);
24542 __tmp.put_i32_le(self.value);
24543 for val in &self.name {
24544 __tmp.put_u8(*val);
24545 }
24546 if matches!(version, MavlinkVersion::V2) {
24547 let len = __tmp.len();
24548 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24549 } else {
24550 __tmp.len()
24551 }
24552 }
24553}
24554#[doc = "id: 372"]
24555#[doc = "Battery information that is static, or requires infrequent update. This message should requested using MAV_CMD_REQUEST_MESSAGE and/or streamed at very low rate. BATTERY_STATUS_V2 is used for higher-rate battery status information."]
24556#[derive(Debug, Clone, PartialEq)]
24557#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24558#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24559pub struct BATTERY_INFO_DATA {
24560 #[doc = "Minimum per-cell voltage when discharging. 0: field not provided."]
24561 pub discharge_minimum_voltage: f32,
24562 #[doc = "Minimum per-cell voltage when charging. 0: field not provided."]
24563 pub charging_minimum_voltage: f32,
24564 #[doc = "Minimum per-cell voltage when resting. 0: field not provided."]
24565 pub resting_minimum_voltage: f32,
24566 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
24567 pub charging_maximum_voltage: f32,
24568 #[doc = "Maximum pack continuous charge current. 0: field not provided."]
24569 pub charging_maximum_current: f32,
24570 #[doc = "Battery nominal voltage. Used for conversion between Wh and Ah. 0: field not provided."]
24571 pub nominal_voltage: f32,
24572 #[doc = "Maximum pack discharge current. 0: field not provided."]
24573 pub discharge_maximum_current: f32,
24574 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
24575 pub discharge_maximum_burst_current: f32,
24576 #[doc = "Fully charged design capacity. 0: field not provided."]
24577 pub design_capacity: f32,
24578 #[doc = "Predicted battery capacity when fully charged (accounting for battery degradation). NAN: field not provided."]
24579 pub full_charge_capacity: f32,
24580 #[doc = "Lifetime count of the number of charge/discharge cycles (<https://en.wikipedia.org/wiki/Charge_cycle>). UINT16_MAX: field not provided."]
24581 pub cycle_count: u16,
24582 #[doc = "Battery weight. 0: field not provided."]
24583 pub weight: u16,
24584 #[doc = "Battery ID"]
24585 pub id: u8,
24586 #[doc = "Function of the battery."]
24587 pub battery_function: MavBatteryFunction,
24588 #[doc = "Type (chemistry) of the battery."]
24589 pub mavtype: MavBatteryType,
24590 #[doc = "State of Health (SOH) estimate. Typically 100% at the time of manufacture and will decrease over time and use. -1: field not provided."]
24591 pub state_of_health: u8,
24592 #[doc = "Number of battery cells in series. 0: field not provided."]
24593 pub cells_in_series: u8,
24594 #[doc = "Manufacture date (DDMMYYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
24595 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24596 pub manufacture_date: [u8; 9],
24597 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
24598 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24599 pub serial_number: [u8; 32],
24600 #[doc = "Battery device name. Formatted as manufacturer name then product name, separated with an underscore (in ASCII characters), 0 terminated. All 0: field not provided."]
24601 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24602 pub name: [u8; 50],
24603}
24604impl BATTERY_INFO_DATA {
24605 pub const ENCODED_LEN: usize = 140usize;
24606 pub const DEFAULT: Self = Self {
24607 discharge_minimum_voltage: 0.0_f32,
24608 charging_minimum_voltage: 0.0_f32,
24609 resting_minimum_voltage: 0.0_f32,
24610 charging_maximum_voltage: 0.0_f32,
24611 charging_maximum_current: 0.0_f32,
24612 nominal_voltage: 0.0_f32,
24613 discharge_maximum_current: 0.0_f32,
24614 discharge_maximum_burst_current: 0.0_f32,
24615 design_capacity: 0.0_f32,
24616 full_charge_capacity: 0.0_f32,
24617 cycle_count: 0_u16,
24618 weight: 0_u16,
24619 id: 0_u8,
24620 battery_function: MavBatteryFunction::DEFAULT,
24621 mavtype: MavBatteryType::DEFAULT,
24622 state_of_health: 0_u8,
24623 cells_in_series: 0_u8,
24624 manufacture_date: [0_u8; 9usize],
24625 serial_number: [0_u8; 32usize],
24626 name: [0_u8; 50usize],
24627 };
24628 #[cfg(feature = "arbitrary")]
24629 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24630 use arbitrary::{Arbitrary, Unstructured};
24631 let mut buf = [0u8; 1024];
24632 rng.fill_bytes(&mut buf);
24633 let mut unstructured = Unstructured::new(&buf);
24634 Self::arbitrary(&mut unstructured).unwrap_or_default()
24635 }
24636}
24637impl Default for BATTERY_INFO_DATA {
24638 fn default() -> Self {
24639 Self::DEFAULT.clone()
24640 }
24641}
24642impl MessageData for BATTERY_INFO_DATA {
24643 type Message = MavMessage;
24644 const ID: u32 = 372u32;
24645 const NAME: &'static str = "BATTERY_INFO";
24646 const EXTRA_CRC: u8 = 26u8;
24647 const ENCODED_LEN: usize = 140usize;
24648 fn deser(
24649 _version: MavlinkVersion,
24650 __input: &[u8],
24651 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24652 let avail_len = __input.len();
24653 let mut payload_buf = [0; Self::ENCODED_LEN];
24654 let mut buf = if avail_len < Self::ENCODED_LEN {
24655 payload_buf[0..avail_len].copy_from_slice(__input);
24656 Bytes::new(&payload_buf)
24657 } else {
24658 Bytes::new(__input)
24659 };
24660 let mut __struct = Self::default();
24661 __struct.discharge_minimum_voltage = buf.get_f32_le();
24662 __struct.charging_minimum_voltage = buf.get_f32_le();
24663 __struct.resting_minimum_voltage = buf.get_f32_le();
24664 __struct.charging_maximum_voltage = buf.get_f32_le();
24665 __struct.charging_maximum_current = buf.get_f32_le();
24666 __struct.nominal_voltage = buf.get_f32_le();
24667 __struct.discharge_maximum_current = buf.get_f32_le();
24668 __struct.discharge_maximum_burst_current = buf.get_f32_le();
24669 __struct.design_capacity = buf.get_f32_le();
24670 __struct.full_charge_capacity = buf.get_f32_le();
24671 __struct.cycle_count = buf.get_u16_le();
24672 __struct.weight = buf.get_u16_le();
24673 __struct.id = buf.get_u8();
24674 let tmp = buf.get_u8();
24675 __struct.battery_function =
24676 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24677 enum_type: "MavBatteryFunction",
24678 value: tmp as u32,
24679 })?;
24680 let tmp = buf.get_u8();
24681 __struct.mavtype =
24682 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24683 enum_type: "MavBatteryType",
24684 value: tmp as u32,
24685 })?;
24686 __struct.state_of_health = buf.get_u8();
24687 __struct.cells_in_series = buf.get_u8();
24688 for v in &mut __struct.manufacture_date {
24689 let val = buf.get_u8();
24690 *v = val;
24691 }
24692 for v in &mut __struct.serial_number {
24693 let val = buf.get_u8();
24694 *v = val;
24695 }
24696 for v in &mut __struct.name {
24697 let val = buf.get_u8();
24698 *v = val;
24699 }
24700 Ok(__struct)
24701 }
24702 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24703 let mut __tmp = BytesMut::new(bytes);
24704 #[allow(clippy::absurd_extreme_comparisons)]
24705 #[allow(unused_comparisons)]
24706 if __tmp.remaining() < Self::ENCODED_LEN {
24707 panic!(
24708 "buffer is too small (need {} bytes, but got {})",
24709 Self::ENCODED_LEN,
24710 __tmp.remaining(),
24711 )
24712 }
24713 __tmp.put_f32_le(self.discharge_minimum_voltage);
24714 __tmp.put_f32_le(self.charging_minimum_voltage);
24715 __tmp.put_f32_le(self.resting_minimum_voltage);
24716 __tmp.put_f32_le(self.charging_maximum_voltage);
24717 __tmp.put_f32_le(self.charging_maximum_current);
24718 __tmp.put_f32_le(self.nominal_voltage);
24719 __tmp.put_f32_le(self.discharge_maximum_current);
24720 __tmp.put_f32_le(self.discharge_maximum_burst_current);
24721 __tmp.put_f32_le(self.design_capacity);
24722 __tmp.put_f32_le(self.full_charge_capacity);
24723 __tmp.put_u16_le(self.cycle_count);
24724 __tmp.put_u16_le(self.weight);
24725 __tmp.put_u8(self.id);
24726 __tmp.put_u8(self.battery_function as u8);
24727 __tmp.put_u8(self.mavtype as u8);
24728 __tmp.put_u8(self.state_of_health);
24729 __tmp.put_u8(self.cells_in_series);
24730 for val in &self.manufacture_date {
24731 __tmp.put_u8(*val);
24732 }
24733 for val in &self.serial_number {
24734 __tmp.put_u8(*val);
24735 }
24736 for val in &self.name {
24737 __tmp.put_u8(*val);
24738 }
24739 if matches!(version, MavlinkVersion::V2) {
24740 let len = __tmp.len();
24741 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24742 } else {
24743 __tmp.len()
24744 }
24745 }
24746}
24747#[doc = "id: 49"]
24748#[doc = "Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message."]
24749#[derive(Debug, Clone, PartialEq)]
24750#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24751#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24752pub struct GPS_GLOBAL_ORIGIN_DATA {
24753 #[doc = "Latitude (WGS84)"]
24754 pub latitude: i32,
24755 #[doc = "Longitude (WGS84)"]
24756 pub longitude: i32,
24757 #[doc = "Altitude (MSL). Positive for up."]
24758 pub altitude: i32,
24759 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24760 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24761 pub time_usec: u64,
24762}
24763impl GPS_GLOBAL_ORIGIN_DATA {
24764 pub const ENCODED_LEN: usize = 20usize;
24765 pub const DEFAULT: Self = Self {
24766 latitude: 0_i32,
24767 longitude: 0_i32,
24768 altitude: 0_i32,
24769 time_usec: 0_u64,
24770 };
24771 #[cfg(feature = "arbitrary")]
24772 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24773 use arbitrary::{Arbitrary, Unstructured};
24774 let mut buf = [0u8; 1024];
24775 rng.fill_bytes(&mut buf);
24776 let mut unstructured = Unstructured::new(&buf);
24777 Self::arbitrary(&mut unstructured).unwrap_or_default()
24778 }
24779}
24780impl Default for GPS_GLOBAL_ORIGIN_DATA {
24781 fn default() -> Self {
24782 Self::DEFAULT.clone()
24783 }
24784}
24785impl MessageData for GPS_GLOBAL_ORIGIN_DATA {
24786 type Message = MavMessage;
24787 const ID: u32 = 49u32;
24788 const NAME: &'static str = "GPS_GLOBAL_ORIGIN";
24789 const EXTRA_CRC: u8 = 39u8;
24790 const ENCODED_LEN: usize = 20usize;
24791 fn deser(
24792 _version: MavlinkVersion,
24793 __input: &[u8],
24794 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24795 let avail_len = __input.len();
24796 let mut payload_buf = [0; Self::ENCODED_LEN];
24797 let mut buf = if avail_len < Self::ENCODED_LEN {
24798 payload_buf[0..avail_len].copy_from_slice(__input);
24799 Bytes::new(&payload_buf)
24800 } else {
24801 Bytes::new(__input)
24802 };
24803 let mut __struct = Self::default();
24804 __struct.latitude = buf.get_i32_le();
24805 __struct.longitude = buf.get_i32_le();
24806 __struct.altitude = buf.get_i32_le();
24807 __struct.time_usec = buf.get_u64_le();
24808 Ok(__struct)
24809 }
24810 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24811 let mut __tmp = BytesMut::new(bytes);
24812 #[allow(clippy::absurd_extreme_comparisons)]
24813 #[allow(unused_comparisons)]
24814 if __tmp.remaining() < Self::ENCODED_LEN {
24815 panic!(
24816 "buffer is too small (need {} bytes, but got {})",
24817 Self::ENCODED_LEN,
24818 __tmp.remaining(),
24819 )
24820 }
24821 __tmp.put_i32_le(self.latitude);
24822 __tmp.put_i32_le(self.longitude);
24823 __tmp.put_i32_le(self.altitude);
24824 __tmp.put_u64_le(self.time_usec);
24825 if matches!(version, MavlinkVersion::V2) {
24826 let len = __tmp.len();
24827 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24828 } else {
24829 __tmp.len()
24830 }
24831 }
24832}
24833#[doc = "id: 89"]
24834#[doc = "The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
24835#[derive(Debug, Clone, PartialEq)]
24836#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24837#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24838pub struct LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
24839 #[doc = "Timestamp (time since system boot)."]
24840 pub time_boot_ms: u32,
24841 #[doc = "X Position"]
24842 pub x: f32,
24843 #[doc = "Y Position"]
24844 pub y: f32,
24845 #[doc = "Z Position"]
24846 pub z: f32,
24847 #[doc = "Roll"]
24848 pub roll: f32,
24849 #[doc = "Pitch"]
24850 pub pitch: f32,
24851 #[doc = "Yaw"]
24852 pub yaw: f32,
24853}
24854impl LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
24855 pub const ENCODED_LEN: usize = 28usize;
24856 pub const DEFAULT: Self = Self {
24857 time_boot_ms: 0_u32,
24858 x: 0.0_f32,
24859 y: 0.0_f32,
24860 z: 0.0_f32,
24861 roll: 0.0_f32,
24862 pitch: 0.0_f32,
24863 yaw: 0.0_f32,
24864 };
24865 #[cfg(feature = "arbitrary")]
24866 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24867 use arbitrary::{Arbitrary, Unstructured};
24868 let mut buf = [0u8; 1024];
24869 rng.fill_bytes(&mut buf);
24870 let mut unstructured = Unstructured::new(&buf);
24871 Self::arbitrary(&mut unstructured).unwrap_or_default()
24872 }
24873}
24874impl Default for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
24875 fn default() -> Self {
24876 Self::DEFAULT.clone()
24877 }
24878}
24879impl MessageData for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
24880 type Message = MavMessage;
24881 const ID: u32 = 89u32;
24882 const NAME: &'static str = "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET";
24883 const EXTRA_CRC: u8 = 231u8;
24884 const ENCODED_LEN: usize = 28usize;
24885 fn deser(
24886 _version: MavlinkVersion,
24887 __input: &[u8],
24888 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24889 let avail_len = __input.len();
24890 let mut payload_buf = [0; Self::ENCODED_LEN];
24891 let mut buf = if avail_len < Self::ENCODED_LEN {
24892 payload_buf[0..avail_len].copy_from_slice(__input);
24893 Bytes::new(&payload_buf)
24894 } else {
24895 Bytes::new(__input)
24896 };
24897 let mut __struct = Self::default();
24898 __struct.time_boot_ms = buf.get_u32_le();
24899 __struct.x = buf.get_f32_le();
24900 __struct.y = buf.get_f32_le();
24901 __struct.z = buf.get_f32_le();
24902 __struct.roll = buf.get_f32_le();
24903 __struct.pitch = buf.get_f32_le();
24904 __struct.yaw = buf.get_f32_le();
24905 Ok(__struct)
24906 }
24907 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24908 let mut __tmp = BytesMut::new(bytes);
24909 #[allow(clippy::absurd_extreme_comparisons)]
24910 #[allow(unused_comparisons)]
24911 if __tmp.remaining() < Self::ENCODED_LEN {
24912 panic!(
24913 "buffer is too small (need {} bytes, but got {})",
24914 Self::ENCODED_LEN,
24915 __tmp.remaining(),
24916 )
24917 }
24918 __tmp.put_u32_le(self.time_boot_ms);
24919 __tmp.put_f32_le(self.x);
24920 __tmp.put_f32_le(self.y);
24921 __tmp.put_f32_le(self.z);
24922 __tmp.put_f32_le(self.roll);
24923 __tmp.put_f32_le(self.pitch);
24924 __tmp.put_f32_le(self.yaw);
24925 if matches!(version, MavlinkVersion::V2) {
24926 let len = __tmp.len();
24927 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24928 } else {
24929 __tmp.len()
24930 }
24931 }
24932}
24933#[doc = "id: 115"]
24934#[doc = "Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations."]
24935#[derive(Debug, Clone, PartialEq)]
24936#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24937#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24938pub struct HIL_STATE_QUATERNION_DATA {
24939 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24940 pub time_usec: u64,
24941 #[doc = "Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)"]
24942 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24943 pub attitude_quaternion: [f32; 4],
24944 #[doc = "Body frame roll / phi angular speed"]
24945 pub rollspeed: f32,
24946 #[doc = "Body frame pitch / theta angular speed"]
24947 pub pitchspeed: f32,
24948 #[doc = "Body frame yaw / psi angular speed"]
24949 pub yawspeed: f32,
24950 #[doc = "Latitude"]
24951 pub lat: i32,
24952 #[doc = "Longitude"]
24953 pub lon: i32,
24954 #[doc = "Altitude"]
24955 pub alt: i32,
24956 #[doc = "Ground X Speed (Latitude)"]
24957 pub vx: i16,
24958 #[doc = "Ground Y Speed (Longitude)"]
24959 pub vy: i16,
24960 #[doc = "Ground Z Speed (Altitude)"]
24961 pub vz: i16,
24962 #[doc = "Indicated airspeed"]
24963 pub ind_airspeed: u16,
24964 #[doc = "True airspeed"]
24965 pub true_airspeed: u16,
24966 #[doc = "X acceleration"]
24967 pub xacc: i16,
24968 #[doc = "Y acceleration"]
24969 pub yacc: i16,
24970 #[doc = "Z acceleration"]
24971 pub zacc: i16,
24972}
24973impl HIL_STATE_QUATERNION_DATA {
24974 pub const ENCODED_LEN: usize = 64usize;
24975 pub const DEFAULT: Self = Self {
24976 time_usec: 0_u64,
24977 attitude_quaternion: [0.0_f32; 4usize],
24978 rollspeed: 0.0_f32,
24979 pitchspeed: 0.0_f32,
24980 yawspeed: 0.0_f32,
24981 lat: 0_i32,
24982 lon: 0_i32,
24983 alt: 0_i32,
24984 vx: 0_i16,
24985 vy: 0_i16,
24986 vz: 0_i16,
24987 ind_airspeed: 0_u16,
24988 true_airspeed: 0_u16,
24989 xacc: 0_i16,
24990 yacc: 0_i16,
24991 zacc: 0_i16,
24992 };
24993 #[cfg(feature = "arbitrary")]
24994 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24995 use arbitrary::{Arbitrary, Unstructured};
24996 let mut buf = [0u8; 1024];
24997 rng.fill_bytes(&mut buf);
24998 let mut unstructured = Unstructured::new(&buf);
24999 Self::arbitrary(&mut unstructured).unwrap_or_default()
25000 }
25001}
25002impl Default for HIL_STATE_QUATERNION_DATA {
25003 fn default() -> Self {
25004 Self::DEFAULT.clone()
25005 }
25006}
25007impl MessageData for HIL_STATE_QUATERNION_DATA {
25008 type Message = MavMessage;
25009 const ID: u32 = 115u32;
25010 const NAME: &'static str = "HIL_STATE_QUATERNION";
25011 const EXTRA_CRC: u8 = 4u8;
25012 const ENCODED_LEN: usize = 64usize;
25013 fn deser(
25014 _version: MavlinkVersion,
25015 __input: &[u8],
25016 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25017 let avail_len = __input.len();
25018 let mut payload_buf = [0; Self::ENCODED_LEN];
25019 let mut buf = if avail_len < Self::ENCODED_LEN {
25020 payload_buf[0..avail_len].copy_from_slice(__input);
25021 Bytes::new(&payload_buf)
25022 } else {
25023 Bytes::new(__input)
25024 };
25025 let mut __struct = Self::default();
25026 __struct.time_usec = buf.get_u64_le();
25027 for v in &mut __struct.attitude_quaternion {
25028 let val = buf.get_f32_le();
25029 *v = val;
25030 }
25031 __struct.rollspeed = buf.get_f32_le();
25032 __struct.pitchspeed = buf.get_f32_le();
25033 __struct.yawspeed = buf.get_f32_le();
25034 __struct.lat = buf.get_i32_le();
25035 __struct.lon = buf.get_i32_le();
25036 __struct.alt = buf.get_i32_le();
25037 __struct.vx = buf.get_i16_le();
25038 __struct.vy = buf.get_i16_le();
25039 __struct.vz = buf.get_i16_le();
25040 __struct.ind_airspeed = buf.get_u16_le();
25041 __struct.true_airspeed = buf.get_u16_le();
25042 __struct.xacc = buf.get_i16_le();
25043 __struct.yacc = buf.get_i16_le();
25044 __struct.zacc = buf.get_i16_le();
25045 Ok(__struct)
25046 }
25047 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25048 let mut __tmp = BytesMut::new(bytes);
25049 #[allow(clippy::absurd_extreme_comparisons)]
25050 #[allow(unused_comparisons)]
25051 if __tmp.remaining() < Self::ENCODED_LEN {
25052 panic!(
25053 "buffer is too small (need {} bytes, but got {})",
25054 Self::ENCODED_LEN,
25055 __tmp.remaining(),
25056 )
25057 }
25058 __tmp.put_u64_le(self.time_usec);
25059 for val in &self.attitude_quaternion {
25060 __tmp.put_f32_le(*val);
25061 }
25062 __tmp.put_f32_le(self.rollspeed);
25063 __tmp.put_f32_le(self.pitchspeed);
25064 __tmp.put_f32_le(self.yawspeed);
25065 __tmp.put_i32_le(self.lat);
25066 __tmp.put_i32_le(self.lon);
25067 __tmp.put_i32_le(self.alt);
25068 __tmp.put_i16_le(self.vx);
25069 __tmp.put_i16_le(self.vy);
25070 __tmp.put_i16_le(self.vz);
25071 __tmp.put_u16_le(self.ind_airspeed);
25072 __tmp.put_u16_le(self.true_airspeed);
25073 __tmp.put_i16_le(self.xacc);
25074 __tmp.put_i16_le(self.yacc);
25075 __tmp.put_i16_le(self.zacc);
25076 if matches!(version, MavlinkVersion::V2) {
25077 let len = __tmp.len();
25078 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25079 } else {
25080 __tmp.len()
25081 }
25082 }
25083}
25084#[doc = "id: 250"]
25085#[doc = "To debug something using a named 3D vector."]
25086#[derive(Debug, Clone, PartialEq)]
25087#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25088#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25089pub struct DEBUG_VECT_DATA {
25090 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
25091 pub time_usec: u64,
25092 #[doc = "x"]
25093 pub x: f32,
25094 #[doc = "y"]
25095 pub y: f32,
25096 #[doc = "z"]
25097 pub z: f32,
25098 #[doc = "Name"]
25099 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25100 pub name: [u8; 10],
25101}
25102impl DEBUG_VECT_DATA {
25103 pub const ENCODED_LEN: usize = 30usize;
25104 pub const DEFAULT: Self = Self {
25105 time_usec: 0_u64,
25106 x: 0.0_f32,
25107 y: 0.0_f32,
25108 z: 0.0_f32,
25109 name: [0_u8; 10usize],
25110 };
25111 #[cfg(feature = "arbitrary")]
25112 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25113 use arbitrary::{Arbitrary, Unstructured};
25114 let mut buf = [0u8; 1024];
25115 rng.fill_bytes(&mut buf);
25116 let mut unstructured = Unstructured::new(&buf);
25117 Self::arbitrary(&mut unstructured).unwrap_or_default()
25118 }
25119}
25120impl Default for DEBUG_VECT_DATA {
25121 fn default() -> Self {
25122 Self::DEFAULT.clone()
25123 }
25124}
25125impl MessageData for DEBUG_VECT_DATA {
25126 type Message = MavMessage;
25127 const ID: u32 = 250u32;
25128 const NAME: &'static str = "DEBUG_VECT";
25129 const EXTRA_CRC: u8 = 49u8;
25130 const ENCODED_LEN: usize = 30usize;
25131 fn deser(
25132 _version: MavlinkVersion,
25133 __input: &[u8],
25134 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25135 let avail_len = __input.len();
25136 let mut payload_buf = [0; Self::ENCODED_LEN];
25137 let mut buf = if avail_len < Self::ENCODED_LEN {
25138 payload_buf[0..avail_len].copy_from_slice(__input);
25139 Bytes::new(&payload_buf)
25140 } else {
25141 Bytes::new(__input)
25142 };
25143 let mut __struct = Self::default();
25144 __struct.time_usec = buf.get_u64_le();
25145 __struct.x = buf.get_f32_le();
25146 __struct.y = buf.get_f32_le();
25147 __struct.z = buf.get_f32_le();
25148 for v in &mut __struct.name {
25149 let val = buf.get_u8();
25150 *v = val;
25151 }
25152 Ok(__struct)
25153 }
25154 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25155 let mut __tmp = BytesMut::new(bytes);
25156 #[allow(clippy::absurd_extreme_comparisons)]
25157 #[allow(unused_comparisons)]
25158 if __tmp.remaining() < Self::ENCODED_LEN {
25159 panic!(
25160 "buffer is too small (need {} bytes, but got {})",
25161 Self::ENCODED_LEN,
25162 __tmp.remaining(),
25163 )
25164 }
25165 __tmp.put_u64_le(self.time_usec);
25166 __tmp.put_f32_le(self.x);
25167 __tmp.put_f32_le(self.y);
25168 __tmp.put_f32_le(self.z);
25169 for val in &self.name {
25170 __tmp.put_u8(*val);
25171 }
25172 if matches!(version, MavlinkVersion::V2) {
25173 let len = __tmp.len();
25174 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25175 } else {
25176 __tmp.len()
25177 }
25178 }
25179}
25180#[doc = "id: 270"]
25181#[doc = "Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE."]
25182#[derive(Debug, Clone, PartialEq)]
25183#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25184#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25185pub struct VIDEO_STREAM_STATUS_DATA {
25186 #[doc = "Frame rate"]
25187 pub framerate: f32,
25188 #[doc = "Bit rate"]
25189 pub bitrate: u32,
25190 #[doc = "Bitmap of stream status flags"]
25191 pub flags: VideoStreamStatusFlags,
25192 #[doc = "Horizontal resolution"]
25193 pub resolution_h: u16,
25194 #[doc = "Vertical resolution"]
25195 pub resolution_v: u16,
25196 #[doc = "Video image rotation clockwise"]
25197 pub rotation: u16,
25198 #[doc = "Horizontal Field of view"]
25199 pub hfov: u16,
25200 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
25201 pub stream_id: u8,
25202 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
25203 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25204 pub camera_device_id: u8,
25205}
25206impl VIDEO_STREAM_STATUS_DATA {
25207 pub const ENCODED_LEN: usize = 20usize;
25208 pub const DEFAULT: Self = Self {
25209 framerate: 0.0_f32,
25210 bitrate: 0_u32,
25211 flags: VideoStreamStatusFlags::DEFAULT,
25212 resolution_h: 0_u16,
25213 resolution_v: 0_u16,
25214 rotation: 0_u16,
25215 hfov: 0_u16,
25216 stream_id: 0_u8,
25217 camera_device_id: 0_u8,
25218 };
25219 #[cfg(feature = "arbitrary")]
25220 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25221 use arbitrary::{Arbitrary, Unstructured};
25222 let mut buf = [0u8; 1024];
25223 rng.fill_bytes(&mut buf);
25224 let mut unstructured = Unstructured::new(&buf);
25225 Self::arbitrary(&mut unstructured).unwrap_or_default()
25226 }
25227}
25228impl Default for VIDEO_STREAM_STATUS_DATA {
25229 fn default() -> Self {
25230 Self::DEFAULT.clone()
25231 }
25232}
25233impl MessageData for VIDEO_STREAM_STATUS_DATA {
25234 type Message = MavMessage;
25235 const ID: u32 = 270u32;
25236 const NAME: &'static str = "VIDEO_STREAM_STATUS";
25237 const EXTRA_CRC: u8 = 59u8;
25238 const ENCODED_LEN: usize = 20usize;
25239 fn deser(
25240 _version: MavlinkVersion,
25241 __input: &[u8],
25242 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25243 let avail_len = __input.len();
25244 let mut payload_buf = [0; Self::ENCODED_LEN];
25245 let mut buf = if avail_len < Self::ENCODED_LEN {
25246 payload_buf[0..avail_len].copy_from_slice(__input);
25247 Bytes::new(&payload_buf)
25248 } else {
25249 Bytes::new(__input)
25250 };
25251 let mut __struct = Self::default();
25252 __struct.framerate = buf.get_f32_le();
25253 __struct.bitrate = buf.get_u32_le();
25254 let tmp = buf.get_u16_le();
25255 __struct.flags = VideoStreamStatusFlags::from_bits(
25256 tmp & VideoStreamStatusFlags::all().bits(),
25257 )
25258 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
25259 flag_type: "VideoStreamStatusFlags",
25260 value: tmp as u32,
25261 })?;
25262 __struct.resolution_h = buf.get_u16_le();
25263 __struct.resolution_v = buf.get_u16_le();
25264 __struct.rotation = buf.get_u16_le();
25265 __struct.hfov = buf.get_u16_le();
25266 __struct.stream_id = buf.get_u8();
25267 __struct.camera_device_id = buf.get_u8();
25268 Ok(__struct)
25269 }
25270 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25271 let mut __tmp = BytesMut::new(bytes);
25272 #[allow(clippy::absurd_extreme_comparisons)]
25273 #[allow(unused_comparisons)]
25274 if __tmp.remaining() < Self::ENCODED_LEN {
25275 panic!(
25276 "buffer is too small (need {} bytes, but got {})",
25277 Self::ENCODED_LEN,
25278 __tmp.remaining(),
25279 )
25280 }
25281 __tmp.put_f32_le(self.framerate);
25282 __tmp.put_u32_le(self.bitrate);
25283 __tmp.put_u16_le(self.flags.bits());
25284 __tmp.put_u16_le(self.resolution_h);
25285 __tmp.put_u16_le(self.resolution_v);
25286 __tmp.put_u16_le(self.rotation);
25287 __tmp.put_u16_le(self.hfov);
25288 __tmp.put_u8(self.stream_id);
25289 __tmp.put_u8(self.camera_device_id);
25290 if matches!(version, MavlinkVersion::V2) {
25291 let len = __tmp.len();
25292 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25293 } else {
25294 __tmp.len()
25295 }
25296 }
25297}
25298#[doc = "id: 288"]
25299#[doc = "High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
25300#[derive(Debug, Clone, PartialEq)]
25301#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25302#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25303pub struct GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
25304 #[doc = "High level gimbal manager flags."]
25305 pub flags: GimbalManagerFlags,
25306 #[doc = "Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
25307 pub pitch: f32,
25308 #[doc = "Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
25309 pub yaw: f32,
25310 #[doc = "Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
25311 pub pitch_rate: f32,
25312 #[doc = "Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
25313 pub yaw_rate: f32,
25314 #[doc = "System ID"]
25315 pub target_system: u8,
25316 #[doc = "Component ID"]
25317 pub target_component: u8,
25318 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
25319 pub gimbal_device_id: u8,
25320}
25321impl GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
25322 pub const ENCODED_LEN: usize = 23usize;
25323 pub const DEFAULT: Self = Self {
25324 flags: GimbalManagerFlags::DEFAULT,
25325 pitch: 0.0_f32,
25326 yaw: 0.0_f32,
25327 pitch_rate: 0.0_f32,
25328 yaw_rate: 0.0_f32,
25329 target_system: 0_u8,
25330 target_component: 0_u8,
25331 gimbal_device_id: 0_u8,
25332 };
25333 #[cfg(feature = "arbitrary")]
25334 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25335 use arbitrary::{Arbitrary, Unstructured};
25336 let mut buf = [0u8; 1024];
25337 rng.fill_bytes(&mut buf);
25338 let mut unstructured = Unstructured::new(&buf);
25339 Self::arbitrary(&mut unstructured).unwrap_or_default()
25340 }
25341}
25342impl Default for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
25343 fn default() -> Self {
25344 Self::DEFAULT.clone()
25345 }
25346}
25347impl MessageData for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
25348 type Message = MavMessage;
25349 const ID: u32 = 288u32;
25350 const NAME: &'static str = "GIMBAL_MANAGER_SET_MANUAL_CONTROL";
25351 const EXTRA_CRC: u8 = 20u8;
25352 const ENCODED_LEN: usize = 23usize;
25353 fn deser(
25354 _version: MavlinkVersion,
25355 __input: &[u8],
25356 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25357 let avail_len = __input.len();
25358 let mut payload_buf = [0; Self::ENCODED_LEN];
25359 let mut buf = if avail_len < Self::ENCODED_LEN {
25360 payload_buf[0..avail_len].copy_from_slice(__input);
25361 Bytes::new(&payload_buf)
25362 } else {
25363 Bytes::new(__input)
25364 };
25365 let mut __struct = Self::default();
25366 let tmp = buf.get_u32_le();
25367 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
25368 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
25369 flag_type: "GimbalManagerFlags",
25370 value: tmp as u32,
25371 })?;
25372 __struct.pitch = buf.get_f32_le();
25373 __struct.yaw = buf.get_f32_le();
25374 __struct.pitch_rate = buf.get_f32_le();
25375 __struct.yaw_rate = buf.get_f32_le();
25376 __struct.target_system = buf.get_u8();
25377 __struct.target_component = buf.get_u8();
25378 __struct.gimbal_device_id = buf.get_u8();
25379 Ok(__struct)
25380 }
25381 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25382 let mut __tmp = BytesMut::new(bytes);
25383 #[allow(clippy::absurd_extreme_comparisons)]
25384 #[allow(unused_comparisons)]
25385 if __tmp.remaining() < Self::ENCODED_LEN {
25386 panic!(
25387 "buffer is too small (need {} bytes, but got {})",
25388 Self::ENCODED_LEN,
25389 __tmp.remaining(),
25390 )
25391 }
25392 __tmp.put_u32_le(self.flags.bits());
25393 __tmp.put_f32_le(self.pitch);
25394 __tmp.put_f32_le(self.yaw);
25395 __tmp.put_f32_le(self.pitch_rate);
25396 __tmp.put_f32_le(self.yaw_rate);
25397 __tmp.put_u8(self.target_system);
25398 __tmp.put_u8(self.target_component);
25399 __tmp.put_u8(self.gimbal_device_id);
25400 if matches!(version, MavlinkVersion::V2) {
25401 let len = __tmp.len();
25402 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25403 } else {
25404 __tmp.len()
25405 }
25406 }
25407}
25408#[doc = "id: 84"]
25409#[doc = "Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system)."]
25410#[derive(Debug, Clone, PartialEq)]
25411#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25412#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25413pub struct SET_POSITION_TARGET_LOCAL_NED_DATA {
25414 #[doc = "Timestamp (time since system boot)."]
25415 pub time_boot_ms: u32,
25416 #[doc = "X Position in NED frame"]
25417 pub x: f32,
25418 #[doc = "Y Position in NED frame"]
25419 pub y: f32,
25420 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
25421 pub z: f32,
25422 #[doc = "X velocity in NED frame"]
25423 pub vx: f32,
25424 #[doc = "Y velocity in NED frame"]
25425 pub vy: f32,
25426 #[doc = "Z velocity in NED frame"]
25427 pub vz: f32,
25428 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
25429 pub afx: f32,
25430 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
25431 pub afy: f32,
25432 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
25433 pub afz: f32,
25434 #[doc = "yaw setpoint"]
25435 pub yaw: f32,
25436 #[doc = "yaw rate setpoint"]
25437 pub yaw_rate: f32,
25438 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
25439 pub type_mask: PositionTargetTypemask,
25440 #[doc = "System ID"]
25441 pub target_system: u8,
25442 #[doc = "Component ID"]
25443 pub target_component: u8,
25444 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
25445 pub coordinate_frame: MavFrame,
25446}
25447impl SET_POSITION_TARGET_LOCAL_NED_DATA {
25448 pub const ENCODED_LEN: usize = 53usize;
25449 pub const DEFAULT: Self = Self {
25450 time_boot_ms: 0_u32,
25451 x: 0.0_f32,
25452 y: 0.0_f32,
25453 z: 0.0_f32,
25454 vx: 0.0_f32,
25455 vy: 0.0_f32,
25456 vz: 0.0_f32,
25457 afx: 0.0_f32,
25458 afy: 0.0_f32,
25459 afz: 0.0_f32,
25460 yaw: 0.0_f32,
25461 yaw_rate: 0.0_f32,
25462 type_mask: PositionTargetTypemask::DEFAULT,
25463 target_system: 0_u8,
25464 target_component: 0_u8,
25465 coordinate_frame: MavFrame::DEFAULT,
25466 };
25467 #[cfg(feature = "arbitrary")]
25468 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25469 use arbitrary::{Arbitrary, Unstructured};
25470 let mut buf = [0u8; 1024];
25471 rng.fill_bytes(&mut buf);
25472 let mut unstructured = Unstructured::new(&buf);
25473 Self::arbitrary(&mut unstructured).unwrap_or_default()
25474 }
25475}
25476impl Default for SET_POSITION_TARGET_LOCAL_NED_DATA {
25477 fn default() -> Self {
25478 Self::DEFAULT.clone()
25479 }
25480}
25481impl MessageData for SET_POSITION_TARGET_LOCAL_NED_DATA {
25482 type Message = MavMessage;
25483 const ID: u32 = 84u32;
25484 const NAME: &'static str = "SET_POSITION_TARGET_LOCAL_NED";
25485 const EXTRA_CRC: u8 = 143u8;
25486 const ENCODED_LEN: usize = 53usize;
25487 fn deser(
25488 _version: MavlinkVersion,
25489 __input: &[u8],
25490 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25491 let avail_len = __input.len();
25492 let mut payload_buf = [0; Self::ENCODED_LEN];
25493 let mut buf = if avail_len < Self::ENCODED_LEN {
25494 payload_buf[0..avail_len].copy_from_slice(__input);
25495 Bytes::new(&payload_buf)
25496 } else {
25497 Bytes::new(__input)
25498 };
25499 let mut __struct = Self::default();
25500 __struct.time_boot_ms = buf.get_u32_le();
25501 __struct.x = buf.get_f32_le();
25502 __struct.y = buf.get_f32_le();
25503 __struct.z = buf.get_f32_le();
25504 __struct.vx = buf.get_f32_le();
25505 __struct.vy = buf.get_f32_le();
25506 __struct.vz = buf.get_f32_le();
25507 __struct.afx = buf.get_f32_le();
25508 __struct.afy = buf.get_f32_le();
25509 __struct.afz = buf.get_f32_le();
25510 __struct.yaw = buf.get_f32_le();
25511 __struct.yaw_rate = buf.get_f32_le();
25512 let tmp = buf.get_u16_le();
25513 __struct.type_mask = PositionTargetTypemask::from_bits(
25514 tmp & PositionTargetTypemask::all().bits(),
25515 )
25516 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
25517 flag_type: "PositionTargetTypemask",
25518 value: tmp as u32,
25519 })?;
25520 __struct.target_system = buf.get_u8();
25521 __struct.target_component = buf.get_u8();
25522 let tmp = buf.get_u8();
25523 __struct.coordinate_frame =
25524 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25525 enum_type: "MavFrame",
25526 value: tmp as u32,
25527 })?;
25528 Ok(__struct)
25529 }
25530 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25531 let mut __tmp = BytesMut::new(bytes);
25532 #[allow(clippy::absurd_extreme_comparisons)]
25533 #[allow(unused_comparisons)]
25534 if __tmp.remaining() < Self::ENCODED_LEN {
25535 panic!(
25536 "buffer is too small (need {} bytes, but got {})",
25537 Self::ENCODED_LEN,
25538 __tmp.remaining(),
25539 )
25540 }
25541 __tmp.put_u32_le(self.time_boot_ms);
25542 __tmp.put_f32_le(self.x);
25543 __tmp.put_f32_le(self.y);
25544 __tmp.put_f32_le(self.z);
25545 __tmp.put_f32_le(self.vx);
25546 __tmp.put_f32_le(self.vy);
25547 __tmp.put_f32_le(self.vz);
25548 __tmp.put_f32_le(self.afx);
25549 __tmp.put_f32_le(self.afy);
25550 __tmp.put_f32_le(self.afz);
25551 __tmp.put_f32_le(self.yaw);
25552 __tmp.put_f32_le(self.yaw_rate);
25553 __tmp.put_u16_le(self.type_mask.bits());
25554 __tmp.put_u8(self.target_system);
25555 __tmp.put_u8(self.target_component);
25556 __tmp.put_u8(self.coordinate_frame as u8);
25557 if matches!(version, MavlinkVersion::V2) {
25558 let len = __tmp.len();
25559 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25560 } else {
25561 __tmp.len()
25562 }
25563 }
25564}
25565#[doc = "id: 324"]
25566#[doc = "Response from a PARAM_EXT_SET message."]
25567#[derive(Debug, Clone, PartialEq)]
25568#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25569#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25570pub struct PARAM_EXT_ACK_DATA {
25571 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
25572 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25573 pub param_id: [u8; 16],
25574 #[doc = "Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)"]
25575 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25576 pub param_value: [u8; 128],
25577 #[doc = "Parameter type."]
25578 pub param_type: MavParamExtType,
25579 #[doc = "Result code."]
25580 pub param_result: ParamAck,
25581}
25582impl PARAM_EXT_ACK_DATA {
25583 pub const ENCODED_LEN: usize = 146usize;
25584 pub const DEFAULT: Self = Self {
25585 param_id: [0_u8; 16usize],
25586 param_value: [0_u8; 128usize],
25587 param_type: MavParamExtType::DEFAULT,
25588 param_result: ParamAck::DEFAULT,
25589 };
25590 #[cfg(feature = "arbitrary")]
25591 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25592 use arbitrary::{Arbitrary, Unstructured};
25593 let mut buf = [0u8; 1024];
25594 rng.fill_bytes(&mut buf);
25595 let mut unstructured = Unstructured::new(&buf);
25596 Self::arbitrary(&mut unstructured).unwrap_or_default()
25597 }
25598}
25599impl Default for PARAM_EXT_ACK_DATA {
25600 fn default() -> Self {
25601 Self::DEFAULT.clone()
25602 }
25603}
25604impl MessageData for PARAM_EXT_ACK_DATA {
25605 type Message = MavMessage;
25606 const ID: u32 = 324u32;
25607 const NAME: &'static str = "PARAM_EXT_ACK";
25608 const EXTRA_CRC: u8 = 132u8;
25609 const ENCODED_LEN: usize = 146usize;
25610 fn deser(
25611 _version: MavlinkVersion,
25612 __input: &[u8],
25613 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25614 let avail_len = __input.len();
25615 let mut payload_buf = [0; Self::ENCODED_LEN];
25616 let mut buf = if avail_len < Self::ENCODED_LEN {
25617 payload_buf[0..avail_len].copy_from_slice(__input);
25618 Bytes::new(&payload_buf)
25619 } else {
25620 Bytes::new(__input)
25621 };
25622 let mut __struct = Self::default();
25623 for v in &mut __struct.param_id {
25624 let val = buf.get_u8();
25625 *v = val;
25626 }
25627 for v in &mut __struct.param_value {
25628 let val = buf.get_u8();
25629 *v = val;
25630 }
25631 let tmp = buf.get_u8();
25632 __struct.param_type =
25633 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25634 enum_type: "MavParamExtType",
25635 value: tmp as u32,
25636 })?;
25637 let tmp = buf.get_u8();
25638 __struct.param_result =
25639 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25640 enum_type: "ParamAck",
25641 value: tmp as u32,
25642 })?;
25643 Ok(__struct)
25644 }
25645 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25646 let mut __tmp = BytesMut::new(bytes);
25647 #[allow(clippy::absurd_extreme_comparisons)]
25648 #[allow(unused_comparisons)]
25649 if __tmp.remaining() < Self::ENCODED_LEN {
25650 panic!(
25651 "buffer is too small (need {} bytes, but got {})",
25652 Self::ENCODED_LEN,
25653 __tmp.remaining(),
25654 )
25655 }
25656 for val in &self.param_id {
25657 __tmp.put_u8(*val);
25658 }
25659 for val in &self.param_value {
25660 __tmp.put_u8(*val);
25661 }
25662 __tmp.put_u8(self.param_type as u8);
25663 __tmp.put_u8(self.param_result as u8);
25664 if matches!(version, MavlinkVersion::V2) {
25665 let len = __tmp.len();
25666 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25667 } else {
25668 __tmp.len()
25669 }
25670 }
25671}
25672#[doc = "id: 54"]
25673#[doc = "Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations."]
25674#[derive(Debug, Clone, PartialEq)]
25675#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25676#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25677pub struct SAFETY_SET_ALLOWED_AREA_DATA {
25678 #[doc = "x position 1 / Latitude 1"]
25679 pub p1x: f32,
25680 #[doc = "y position 1 / Longitude 1"]
25681 pub p1y: f32,
25682 #[doc = "z position 1 / Altitude 1"]
25683 pub p1z: f32,
25684 #[doc = "x position 2 / Latitude 2"]
25685 pub p2x: f32,
25686 #[doc = "y position 2 / Longitude 2"]
25687 pub p2y: f32,
25688 #[doc = "z position 2 / Altitude 2"]
25689 pub p2z: f32,
25690 #[doc = "System ID"]
25691 pub target_system: u8,
25692 #[doc = "Component ID"]
25693 pub target_component: u8,
25694 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
25695 pub frame: MavFrame,
25696}
25697impl SAFETY_SET_ALLOWED_AREA_DATA {
25698 pub const ENCODED_LEN: usize = 27usize;
25699 pub const DEFAULT: Self = Self {
25700 p1x: 0.0_f32,
25701 p1y: 0.0_f32,
25702 p1z: 0.0_f32,
25703 p2x: 0.0_f32,
25704 p2y: 0.0_f32,
25705 p2z: 0.0_f32,
25706 target_system: 0_u8,
25707 target_component: 0_u8,
25708 frame: MavFrame::DEFAULT,
25709 };
25710 #[cfg(feature = "arbitrary")]
25711 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25712 use arbitrary::{Arbitrary, Unstructured};
25713 let mut buf = [0u8; 1024];
25714 rng.fill_bytes(&mut buf);
25715 let mut unstructured = Unstructured::new(&buf);
25716 Self::arbitrary(&mut unstructured).unwrap_or_default()
25717 }
25718}
25719impl Default for SAFETY_SET_ALLOWED_AREA_DATA {
25720 fn default() -> Self {
25721 Self::DEFAULT.clone()
25722 }
25723}
25724impl MessageData for SAFETY_SET_ALLOWED_AREA_DATA {
25725 type Message = MavMessage;
25726 const ID: u32 = 54u32;
25727 const NAME: &'static str = "SAFETY_SET_ALLOWED_AREA";
25728 const EXTRA_CRC: u8 = 15u8;
25729 const ENCODED_LEN: usize = 27usize;
25730 fn deser(
25731 _version: MavlinkVersion,
25732 __input: &[u8],
25733 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25734 let avail_len = __input.len();
25735 let mut payload_buf = [0; Self::ENCODED_LEN];
25736 let mut buf = if avail_len < Self::ENCODED_LEN {
25737 payload_buf[0..avail_len].copy_from_slice(__input);
25738 Bytes::new(&payload_buf)
25739 } else {
25740 Bytes::new(__input)
25741 };
25742 let mut __struct = Self::default();
25743 __struct.p1x = buf.get_f32_le();
25744 __struct.p1y = buf.get_f32_le();
25745 __struct.p1z = buf.get_f32_le();
25746 __struct.p2x = buf.get_f32_le();
25747 __struct.p2y = buf.get_f32_le();
25748 __struct.p2z = buf.get_f32_le();
25749 __struct.target_system = buf.get_u8();
25750 __struct.target_component = buf.get_u8();
25751 let tmp = buf.get_u8();
25752 __struct.frame =
25753 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25754 enum_type: "MavFrame",
25755 value: tmp as u32,
25756 })?;
25757 Ok(__struct)
25758 }
25759 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25760 let mut __tmp = BytesMut::new(bytes);
25761 #[allow(clippy::absurd_extreme_comparisons)]
25762 #[allow(unused_comparisons)]
25763 if __tmp.remaining() < Self::ENCODED_LEN {
25764 panic!(
25765 "buffer is too small (need {} bytes, but got {})",
25766 Self::ENCODED_LEN,
25767 __tmp.remaining(),
25768 )
25769 }
25770 __tmp.put_f32_le(self.p1x);
25771 __tmp.put_f32_le(self.p1y);
25772 __tmp.put_f32_le(self.p1z);
25773 __tmp.put_f32_le(self.p2x);
25774 __tmp.put_f32_le(self.p2y);
25775 __tmp.put_f32_le(self.p2z);
25776 __tmp.put_u8(self.target_system);
25777 __tmp.put_u8(self.target_component);
25778 __tmp.put_u8(self.frame as u8);
25779 if matches!(version, MavlinkVersion::V2) {
25780 let len = __tmp.len();
25781 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25782 } else {
25783 __tmp.len()
25784 }
25785 }
25786}
25787#[doc = "id: 76"]
25788#[doc = "Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
25789#[derive(Debug, Clone, PartialEq)]
25790#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25791#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25792pub struct COMMAND_LONG_DATA {
25793 #[doc = "Parameter 1 (for the specific command)."]
25794 pub param1: f32,
25795 #[doc = "Parameter 2 (for the specific command)."]
25796 pub param2: f32,
25797 #[doc = "Parameter 3 (for the specific command)."]
25798 pub param3: f32,
25799 #[doc = "Parameter 4 (for the specific command)."]
25800 pub param4: f32,
25801 #[doc = "Parameter 5 (for the specific command)."]
25802 pub param5: f32,
25803 #[doc = "Parameter 6 (for the specific command)."]
25804 pub param6: f32,
25805 #[doc = "Parameter 7 (for the specific command)."]
25806 pub param7: f32,
25807 #[doc = "Command ID (of command to send)."]
25808 pub command: MavCmd,
25809 #[doc = "System which should execute the command"]
25810 pub target_system: u8,
25811 #[doc = "Component which should execute the command, 0 for all components"]
25812 pub target_component: u8,
25813 #[doc = "0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)"]
25814 pub confirmation: u8,
25815}
25816impl COMMAND_LONG_DATA {
25817 pub const ENCODED_LEN: usize = 33usize;
25818 pub const DEFAULT: Self = Self {
25819 param1: 0.0_f32,
25820 param2: 0.0_f32,
25821 param3: 0.0_f32,
25822 param4: 0.0_f32,
25823 param5: 0.0_f32,
25824 param6: 0.0_f32,
25825 param7: 0.0_f32,
25826 command: MavCmd::DEFAULT,
25827 target_system: 0_u8,
25828 target_component: 0_u8,
25829 confirmation: 0_u8,
25830 };
25831 #[cfg(feature = "arbitrary")]
25832 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25833 use arbitrary::{Arbitrary, Unstructured};
25834 let mut buf = [0u8; 1024];
25835 rng.fill_bytes(&mut buf);
25836 let mut unstructured = Unstructured::new(&buf);
25837 Self::arbitrary(&mut unstructured).unwrap_or_default()
25838 }
25839}
25840impl Default for COMMAND_LONG_DATA {
25841 fn default() -> Self {
25842 Self::DEFAULT.clone()
25843 }
25844}
25845impl MessageData for COMMAND_LONG_DATA {
25846 type Message = MavMessage;
25847 const ID: u32 = 76u32;
25848 const NAME: &'static str = "COMMAND_LONG";
25849 const EXTRA_CRC: u8 = 152u8;
25850 const ENCODED_LEN: usize = 33usize;
25851 fn deser(
25852 _version: MavlinkVersion,
25853 __input: &[u8],
25854 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25855 let avail_len = __input.len();
25856 let mut payload_buf = [0; Self::ENCODED_LEN];
25857 let mut buf = if avail_len < Self::ENCODED_LEN {
25858 payload_buf[0..avail_len].copy_from_slice(__input);
25859 Bytes::new(&payload_buf)
25860 } else {
25861 Bytes::new(__input)
25862 };
25863 let mut __struct = Self::default();
25864 __struct.param1 = buf.get_f32_le();
25865 __struct.param2 = buf.get_f32_le();
25866 __struct.param3 = buf.get_f32_le();
25867 __struct.param4 = buf.get_f32_le();
25868 __struct.param5 = buf.get_f32_le();
25869 __struct.param6 = buf.get_f32_le();
25870 __struct.param7 = buf.get_f32_le();
25871 let tmp = buf.get_u16_le();
25872 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
25873 ::mavlink_core::error::ParserError::InvalidEnum {
25874 enum_type: "MavCmd",
25875 value: tmp as u32,
25876 },
25877 )?;
25878 __struct.target_system = buf.get_u8();
25879 __struct.target_component = buf.get_u8();
25880 __struct.confirmation = buf.get_u8();
25881 Ok(__struct)
25882 }
25883 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25884 let mut __tmp = BytesMut::new(bytes);
25885 #[allow(clippy::absurd_extreme_comparisons)]
25886 #[allow(unused_comparisons)]
25887 if __tmp.remaining() < Self::ENCODED_LEN {
25888 panic!(
25889 "buffer is too small (need {} bytes, but got {})",
25890 Self::ENCODED_LEN,
25891 __tmp.remaining(),
25892 )
25893 }
25894 __tmp.put_f32_le(self.param1);
25895 __tmp.put_f32_le(self.param2);
25896 __tmp.put_f32_le(self.param3);
25897 __tmp.put_f32_le(self.param4);
25898 __tmp.put_f32_le(self.param5);
25899 __tmp.put_f32_le(self.param6);
25900 __tmp.put_f32_le(self.param7);
25901 __tmp.put_u16_le(self.command as u16);
25902 __tmp.put_u8(self.target_system);
25903 __tmp.put_u8(self.target_component);
25904 __tmp.put_u8(self.confirmation);
25905 if matches!(version, MavlinkVersion::V2) {
25906 let len = __tmp.len();
25907 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25908 } else {
25909 __tmp.len()
25910 }
25911 }
25912}
25913#[doc = "id: 265"]
25914#[doc = "Orientation of a mount."]
25915#[derive(Debug, Clone, PartialEq)]
25916#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25917#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25918pub struct MOUNT_ORIENTATION_DATA {
25919 #[doc = "Timestamp (time since system boot)."]
25920 pub time_boot_ms: u32,
25921 #[doc = "Roll in global frame (set to NaN for invalid)."]
25922 pub roll: f32,
25923 #[doc = "Pitch in global frame (set to NaN for invalid)."]
25924 pub pitch: f32,
25925 #[doc = "Yaw relative to vehicle (set to NaN for invalid)."]
25926 pub yaw: f32,
25927 #[doc = "Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid)."]
25928 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25929 pub yaw_absolute: f32,
25930}
25931impl MOUNT_ORIENTATION_DATA {
25932 pub const ENCODED_LEN: usize = 20usize;
25933 pub const DEFAULT: Self = Self {
25934 time_boot_ms: 0_u32,
25935 roll: 0.0_f32,
25936 pitch: 0.0_f32,
25937 yaw: 0.0_f32,
25938 yaw_absolute: 0.0_f32,
25939 };
25940 #[cfg(feature = "arbitrary")]
25941 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25942 use arbitrary::{Arbitrary, Unstructured};
25943 let mut buf = [0u8; 1024];
25944 rng.fill_bytes(&mut buf);
25945 let mut unstructured = Unstructured::new(&buf);
25946 Self::arbitrary(&mut unstructured).unwrap_or_default()
25947 }
25948}
25949impl Default for MOUNT_ORIENTATION_DATA {
25950 fn default() -> Self {
25951 Self::DEFAULT.clone()
25952 }
25953}
25954impl MessageData for MOUNT_ORIENTATION_DATA {
25955 type Message = MavMessage;
25956 const ID: u32 = 265u32;
25957 const NAME: &'static str = "MOUNT_ORIENTATION";
25958 const EXTRA_CRC: u8 = 26u8;
25959 const ENCODED_LEN: usize = 20usize;
25960 fn deser(
25961 _version: MavlinkVersion,
25962 __input: &[u8],
25963 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25964 let avail_len = __input.len();
25965 let mut payload_buf = [0; Self::ENCODED_LEN];
25966 let mut buf = if avail_len < Self::ENCODED_LEN {
25967 payload_buf[0..avail_len].copy_from_slice(__input);
25968 Bytes::new(&payload_buf)
25969 } else {
25970 Bytes::new(__input)
25971 };
25972 let mut __struct = Self::default();
25973 __struct.time_boot_ms = buf.get_u32_le();
25974 __struct.roll = buf.get_f32_le();
25975 __struct.pitch = buf.get_f32_le();
25976 __struct.yaw = buf.get_f32_le();
25977 __struct.yaw_absolute = buf.get_f32_le();
25978 Ok(__struct)
25979 }
25980 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25981 let mut __tmp = BytesMut::new(bytes);
25982 #[allow(clippy::absurd_extreme_comparisons)]
25983 #[allow(unused_comparisons)]
25984 if __tmp.remaining() < Self::ENCODED_LEN {
25985 panic!(
25986 "buffer is too small (need {} bytes, but got {})",
25987 Self::ENCODED_LEN,
25988 __tmp.remaining(),
25989 )
25990 }
25991 __tmp.put_u32_le(self.time_boot_ms);
25992 __tmp.put_f32_le(self.roll);
25993 __tmp.put_f32_le(self.pitch);
25994 __tmp.put_f32_le(self.yaw);
25995 __tmp.put_f32_le(self.yaw_absolute);
25996 if matches!(version, MavlinkVersion::V2) {
25997 let len = __tmp.len();
25998 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25999 } else {
26000 __tmp.len()
26001 }
26002 }
26003}
26004#[doc = "id: 125"]
26005#[doc = "Power supply status."]
26006#[derive(Debug, Clone, PartialEq)]
26007#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26008#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26009pub struct POWER_STATUS_DATA {
26010 #[doc = "5V rail voltage."]
26011 pub Vcc: u16,
26012 #[doc = "Servo rail voltage."]
26013 pub Vservo: u16,
26014 #[doc = "Bitmap of power supply status flags."]
26015 pub flags: MavPowerStatus,
26016}
26017impl POWER_STATUS_DATA {
26018 pub const ENCODED_LEN: usize = 6usize;
26019 pub const DEFAULT: Self = Self {
26020 Vcc: 0_u16,
26021 Vservo: 0_u16,
26022 flags: MavPowerStatus::DEFAULT,
26023 };
26024 #[cfg(feature = "arbitrary")]
26025 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26026 use arbitrary::{Arbitrary, Unstructured};
26027 let mut buf = [0u8; 1024];
26028 rng.fill_bytes(&mut buf);
26029 let mut unstructured = Unstructured::new(&buf);
26030 Self::arbitrary(&mut unstructured).unwrap_or_default()
26031 }
26032}
26033impl Default for POWER_STATUS_DATA {
26034 fn default() -> Self {
26035 Self::DEFAULT.clone()
26036 }
26037}
26038impl MessageData for POWER_STATUS_DATA {
26039 type Message = MavMessage;
26040 const ID: u32 = 125u32;
26041 const NAME: &'static str = "POWER_STATUS";
26042 const EXTRA_CRC: u8 = 203u8;
26043 const ENCODED_LEN: usize = 6usize;
26044 fn deser(
26045 _version: MavlinkVersion,
26046 __input: &[u8],
26047 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26048 let avail_len = __input.len();
26049 let mut payload_buf = [0; Self::ENCODED_LEN];
26050 let mut buf = if avail_len < Self::ENCODED_LEN {
26051 payload_buf[0..avail_len].copy_from_slice(__input);
26052 Bytes::new(&payload_buf)
26053 } else {
26054 Bytes::new(__input)
26055 };
26056 let mut __struct = Self::default();
26057 __struct.Vcc = buf.get_u16_le();
26058 __struct.Vservo = buf.get_u16_le();
26059 let tmp = buf.get_u16_le();
26060 __struct.flags = MavPowerStatus::from_bits(tmp & MavPowerStatus::all().bits()).ok_or(
26061 ::mavlink_core::error::ParserError::InvalidFlag {
26062 flag_type: "MavPowerStatus",
26063 value: tmp as u32,
26064 },
26065 )?;
26066 Ok(__struct)
26067 }
26068 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26069 let mut __tmp = BytesMut::new(bytes);
26070 #[allow(clippy::absurd_extreme_comparisons)]
26071 #[allow(unused_comparisons)]
26072 if __tmp.remaining() < Self::ENCODED_LEN {
26073 panic!(
26074 "buffer is too small (need {} bytes, but got {})",
26075 Self::ENCODED_LEN,
26076 __tmp.remaining(),
26077 )
26078 }
26079 __tmp.put_u16_le(self.Vcc);
26080 __tmp.put_u16_le(self.Vservo);
26081 __tmp.put_u16_le(self.flags.bits());
26082 if matches!(version, MavlinkVersion::V2) {
26083 let len = __tmp.len();
26084 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26085 } else {
26086 __tmp.len()
26087 }
26088 }
26089}
26090#[doc = "id: 6"]
26091#[doc = "Accept / deny control of this MAV."]
26092#[derive(Debug, Clone, PartialEq)]
26093#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26094#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26095pub struct CHANGE_OPERATOR_CONTROL_ACK_DATA {
26096 #[doc = "ID of the GCS this message"]
26097 pub gcs_system_id: u8,
26098 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
26099 pub control_request: u8,
26100 #[doc = "0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control"]
26101 pub ack: u8,
26102}
26103impl CHANGE_OPERATOR_CONTROL_ACK_DATA {
26104 pub const ENCODED_LEN: usize = 3usize;
26105 pub const DEFAULT: Self = Self {
26106 gcs_system_id: 0_u8,
26107 control_request: 0_u8,
26108 ack: 0_u8,
26109 };
26110 #[cfg(feature = "arbitrary")]
26111 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26112 use arbitrary::{Arbitrary, Unstructured};
26113 let mut buf = [0u8; 1024];
26114 rng.fill_bytes(&mut buf);
26115 let mut unstructured = Unstructured::new(&buf);
26116 Self::arbitrary(&mut unstructured).unwrap_or_default()
26117 }
26118}
26119impl Default for CHANGE_OPERATOR_CONTROL_ACK_DATA {
26120 fn default() -> Self {
26121 Self::DEFAULT.clone()
26122 }
26123}
26124impl MessageData for CHANGE_OPERATOR_CONTROL_ACK_DATA {
26125 type Message = MavMessage;
26126 const ID: u32 = 6u32;
26127 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL_ACK";
26128 const EXTRA_CRC: u8 = 104u8;
26129 const ENCODED_LEN: usize = 3usize;
26130 fn deser(
26131 _version: MavlinkVersion,
26132 __input: &[u8],
26133 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26134 let avail_len = __input.len();
26135 let mut payload_buf = [0; Self::ENCODED_LEN];
26136 let mut buf = if avail_len < Self::ENCODED_LEN {
26137 payload_buf[0..avail_len].copy_from_slice(__input);
26138 Bytes::new(&payload_buf)
26139 } else {
26140 Bytes::new(__input)
26141 };
26142 let mut __struct = Self::default();
26143 __struct.gcs_system_id = buf.get_u8();
26144 __struct.control_request = buf.get_u8();
26145 __struct.ack = buf.get_u8();
26146 Ok(__struct)
26147 }
26148 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26149 let mut __tmp = BytesMut::new(bytes);
26150 #[allow(clippy::absurd_extreme_comparisons)]
26151 #[allow(unused_comparisons)]
26152 if __tmp.remaining() < Self::ENCODED_LEN {
26153 panic!(
26154 "buffer is too small (need {} bytes, but got {})",
26155 Self::ENCODED_LEN,
26156 __tmp.remaining(),
26157 )
26158 }
26159 __tmp.put_u8(self.gcs_system_id);
26160 __tmp.put_u8(self.control_request);
26161 __tmp.put_u8(self.ack);
26162 if matches!(version, MavlinkVersion::V2) {
26163 let len = __tmp.len();
26164 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26165 } else {
26166 __tmp.len()
26167 }
26168 }
26169}
26170#[doc = "id: 24"]
26171#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
26172#[derive(Debug, Clone, PartialEq)]
26173#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26174#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26175pub struct GPS_RAW_INT_DATA {
26176 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26177 pub time_usec: u64,
26178 #[doc = "Latitude (WGS84, EGM96 ellipsoid)"]
26179 pub lat: i32,
26180 #[doc = "Longitude (WGS84, EGM96 ellipsoid)"]
26181 pub lon: i32,
26182 #[doc = "Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude."]
26183 pub alt: i32,
26184 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
26185 pub eph: u16,
26186 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
26187 pub epv: u16,
26188 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
26189 pub vel: u16,
26190 #[doc = "Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
26191 pub cog: u16,
26192 #[doc = "GPS fix type."]
26193 pub fix_type: GpsFixType,
26194 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
26195 pub satellites_visible: u8,
26196 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
26197 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26198 pub alt_ellipsoid: i32,
26199 #[doc = "Position uncertainty."]
26200 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26201 pub h_acc: u32,
26202 #[doc = "Altitude uncertainty."]
26203 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26204 pub v_acc: u32,
26205 #[doc = "Speed uncertainty."]
26206 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26207 pub vel_acc: u32,
26208 #[doc = "Heading / track uncertainty"]
26209 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26210 pub hdg_acc: u32,
26211 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
26212 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26213 pub yaw: u16,
26214}
26215impl GPS_RAW_INT_DATA {
26216 pub const ENCODED_LEN: usize = 52usize;
26217 pub const DEFAULT: Self = Self {
26218 time_usec: 0_u64,
26219 lat: 0_i32,
26220 lon: 0_i32,
26221 alt: 0_i32,
26222 eph: 0_u16,
26223 epv: 0_u16,
26224 vel: 0_u16,
26225 cog: 0_u16,
26226 fix_type: GpsFixType::DEFAULT,
26227 satellites_visible: 0_u8,
26228 alt_ellipsoid: 0_i32,
26229 h_acc: 0_u32,
26230 v_acc: 0_u32,
26231 vel_acc: 0_u32,
26232 hdg_acc: 0_u32,
26233 yaw: 0_u16,
26234 };
26235 #[cfg(feature = "arbitrary")]
26236 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26237 use arbitrary::{Arbitrary, Unstructured};
26238 let mut buf = [0u8; 1024];
26239 rng.fill_bytes(&mut buf);
26240 let mut unstructured = Unstructured::new(&buf);
26241 Self::arbitrary(&mut unstructured).unwrap_or_default()
26242 }
26243}
26244impl Default for GPS_RAW_INT_DATA {
26245 fn default() -> Self {
26246 Self::DEFAULT.clone()
26247 }
26248}
26249impl MessageData for GPS_RAW_INT_DATA {
26250 type Message = MavMessage;
26251 const ID: u32 = 24u32;
26252 const NAME: &'static str = "GPS_RAW_INT";
26253 const EXTRA_CRC: u8 = 24u8;
26254 const ENCODED_LEN: usize = 52usize;
26255 fn deser(
26256 _version: MavlinkVersion,
26257 __input: &[u8],
26258 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26259 let avail_len = __input.len();
26260 let mut payload_buf = [0; Self::ENCODED_LEN];
26261 let mut buf = if avail_len < Self::ENCODED_LEN {
26262 payload_buf[0..avail_len].copy_from_slice(__input);
26263 Bytes::new(&payload_buf)
26264 } else {
26265 Bytes::new(__input)
26266 };
26267 let mut __struct = Self::default();
26268 __struct.time_usec = buf.get_u64_le();
26269 __struct.lat = buf.get_i32_le();
26270 __struct.lon = buf.get_i32_le();
26271 __struct.alt = buf.get_i32_le();
26272 __struct.eph = buf.get_u16_le();
26273 __struct.epv = buf.get_u16_le();
26274 __struct.vel = buf.get_u16_le();
26275 __struct.cog = buf.get_u16_le();
26276 let tmp = buf.get_u8();
26277 __struct.fix_type =
26278 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26279 enum_type: "GpsFixType",
26280 value: tmp as u32,
26281 })?;
26282 __struct.satellites_visible = buf.get_u8();
26283 __struct.alt_ellipsoid = buf.get_i32_le();
26284 __struct.h_acc = buf.get_u32_le();
26285 __struct.v_acc = buf.get_u32_le();
26286 __struct.vel_acc = buf.get_u32_le();
26287 __struct.hdg_acc = buf.get_u32_le();
26288 __struct.yaw = buf.get_u16_le();
26289 Ok(__struct)
26290 }
26291 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26292 let mut __tmp = BytesMut::new(bytes);
26293 #[allow(clippy::absurd_extreme_comparisons)]
26294 #[allow(unused_comparisons)]
26295 if __tmp.remaining() < Self::ENCODED_LEN {
26296 panic!(
26297 "buffer is too small (need {} bytes, but got {})",
26298 Self::ENCODED_LEN,
26299 __tmp.remaining(),
26300 )
26301 }
26302 __tmp.put_u64_le(self.time_usec);
26303 __tmp.put_i32_le(self.lat);
26304 __tmp.put_i32_le(self.lon);
26305 __tmp.put_i32_le(self.alt);
26306 __tmp.put_u16_le(self.eph);
26307 __tmp.put_u16_le(self.epv);
26308 __tmp.put_u16_le(self.vel);
26309 __tmp.put_u16_le(self.cog);
26310 __tmp.put_u8(self.fix_type as u8);
26311 __tmp.put_u8(self.satellites_visible);
26312 __tmp.put_i32_le(self.alt_ellipsoid);
26313 __tmp.put_u32_le(self.h_acc);
26314 __tmp.put_u32_le(self.v_acc);
26315 __tmp.put_u32_le(self.vel_acc);
26316 __tmp.put_u32_le(self.hdg_acc);
26317 __tmp.put_u16_le(self.yaw);
26318 if matches!(version, MavlinkVersion::V2) {
26319 let len = __tmp.len();
26320 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26321 } else {
26322 __tmp.len()
26323 }
26324 }
26325}
26326#[doc = "id: 108"]
26327#[doc = "Status of simulation environment, if used."]
26328#[derive(Debug, Clone, PartialEq)]
26329#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26330#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26331pub struct SIM_STATE_DATA {
26332 #[doc = "True attitude quaternion component 1, w (1 in null-rotation)"]
26333 pub q1: f32,
26334 #[doc = "True attitude quaternion component 2, x (0 in null-rotation)"]
26335 pub q2: f32,
26336 #[doc = "True attitude quaternion component 3, y (0 in null-rotation)"]
26337 pub q3: f32,
26338 #[doc = "True attitude quaternion component 4, z (0 in null-rotation)"]
26339 pub q4: f32,
26340 #[doc = "Attitude roll expressed as Euler angles, not recommended except for human-readable outputs"]
26341 pub roll: f32,
26342 #[doc = "Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs"]
26343 pub pitch: f32,
26344 #[doc = "Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs"]
26345 pub yaw: f32,
26346 #[doc = "X acceleration"]
26347 pub xacc: f32,
26348 #[doc = "Y acceleration"]
26349 pub yacc: f32,
26350 #[doc = "Z acceleration"]
26351 pub zacc: f32,
26352 #[doc = "Angular speed around X axis"]
26353 pub xgyro: f32,
26354 #[doc = "Angular speed around Y axis"]
26355 pub ygyro: f32,
26356 #[doc = "Angular speed around Z axis"]
26357 pub zgyro: f32,
26358 #[doc = "Latitude (lower precision). Both this and the lat_int field should be set."]
26359 pub lat: f32,
26360 #[doc = "Longitude (lower precision). Both this and the lon_int field should be set."]
26361 pub lon: f32,
26362 #[doc = "Altitude"]
26363 pub alt: f32,
26364 #[doc = "Horizontal position standard deviation"]
26365 pub std_dev_horz: f32,
26366 #[doc = "Vertical position standard deviation"]
26367 pub std_dev_vert: f32,
26368 #[doc = "True velocity in north direction in earth-fixed NED frame"]
26369 pub vn: f32,
26370 #[doc = "True velocity in east direction in earth-fixed NED frame"]
26371 pub ve: f32,
26372 #[doc = "True velocity in down direction in earth-fixed NED frame"]
26373 pub vd: f32,
26374 #[doc = "Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred)."]
26375 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26376 pub lat_int: i32,
26377 #[doc = "Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred)."]
26378 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26379 pub lon_int: i32,
26380}
26381impl SIM_STATE_DATA {
26382 pub const ENCODED_LEN: usize = 92usize;
26383 pub const DEFAULT: Self = Self {
26384 q1: 0.0_f32,
26385 q2: 0.0_f32,
26386 q3: 0.0_f32,
26387 q4: 0.0_f32,
26388 roll: 0.0_f32,
26389 pitch: 0.0_f32,
26390 yaw: 0.0_f32,
26391 xacc: 0.0_f32,
26392 yacc: 0.0_f32,
26393 zacc: 0.0_f32,
26394 xgyro: 0.0_f32,
26395 ygyro: 0.0_f32,
26396 zgyro: 0.0_f32,
26397 lat: 0.0_f32,
26398 lon: 0.0_f32,
26399 alt: 0.0_f32,
26400 std_dev_horz: 0.0_f32,
26401 std_dev_vert: 0.0_f32,
26402 vn: 0.0_f32,
26403 ve: 0.0_f32,
26404 vd: 0.0_f32,
26405 lat_int: 0_i32,
26406 lon_int: 0_i32,
26407 };
26408 #[cfg(feature = "arbitrary")]
26409 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26410 use arbitrary::{Arbitrary, Unstructured};
26411 let mut buf = [0u8; 1024];
26412 rng.fill_bytes(&mut buf);
26413 let mut unstructured = Unstructured::new(&buf);
26414 Self::arbitrary(&mut unstructured).unwrap_or_default()
26415 }
26416}
26417impl Default for SIM_STATE_DATA {
26418 fn default() -> Self {
26419 Self::DEFAULT.clone()
26420 }
26421}
26422impl MessageData for SIM_STATE_DATA {
26423 type Message = MavMessage;
26424 const ID: u32 = 108u32;
26425 const NAME: &'static str = "SIM_STATE";
26426 const EXTRA_CRC: u8 = 32u8;
26427 const ENCODED_LEN: usize = 92usize;
26428 fn deser(
26429 _version: MavlinkVersion,
26430 __input: &[u8],
26431 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26432 let avail_len = __input.len();
26433 let mut payload_buf = [0; Self::ENCODED_LEN];
26434 let mut buf = if avail_len < Self::ENCODED_LEN {
26435 payload_buf[0..avail_len].copy_from_slice(__input);
26436 Bytes::new(&payload_buf)
26437 } else {
26438 Bytes::new(__input)
26439 };
26440 let mut __struct = Self::default();
26441 __struct.q1 = buf.get_f32_le();
26442 __struct.q2 = buf.get_f32_le();
26443 __struct.q3 = buf.get_f32_le();
26444 __struct.q4 = buf.get_f32_le();
26445 __struct.roll = buf.get_f32_le();
26446 __struct.pitch = buf.get_f32_le();
26447 __struct.yaw = buf.get_f32_le();
26448 __struct.xacc = buf.get_f32_le();
26449 __struct.yacc = buf.get_f32_le();
26450 __struct.zacc = buf.get_f32_le();
26451 __struct.xgyro = buf.get_f32_le();
26452 __struct.ygyro = buf.get_f32_le();
26453 __struct.zgyro = buf.get_f32_le();
26454 __struct.lat = buf.get_f32_le();
26455 __struct.lon = buf.get_f32_le();
26456 __struct.alt = buf.get_f32_le();
26457 __struct.std_dev_horz = buf.get_f32_le();
26458 __struct.std_dev_vert = buf.get_f32_le();
26459 __struct.vn = buf.get_f32_le();
26460 __struct.ve = buf.get_f32_le();
26461 __struct.vd = buf.get_f32_le();
26462 __struct.lat_int = buf.get_i32_le();
26463 __struct.lon_int = buf.get_i32_le();
26464 Ok(__struct)
26465 }
26466 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26467 let mut __tmp = BytesMut::new(bytes);
26468 #[allow(clippy::absurd_extreme_comparisons)]
26469 #[allow(unused_comparisons)]
26470 if __tmp.remaining() < Self::ENCODED_LEN {
26471 panic!(
26472 "buffer is too small (need {} bytes, but got {})",
26473 Self::ENCODED_LEN,
26474 __tmp.remaining(),
26475 )
26476 }
26477 __tmp.put_f32_le(self.q1);
26478 __tmp.put_f32_le(self.q2);
26479 __tmp.put_f32_le(self.q3);
26480 __tmp.put_f32_le(self.q4);
26481 __tmp.put_f32_le(self.roll);
26482 __tmp.put_f32_le(self.pitch);
26483 __tmp.put_f32_le(self.yaw);
26484 __tmp.put_f32_le(self.xacc);
26485 __tmp.put_f32_le(self.yacc);
26486 __tmp.put_f32_le(self.zacc);
26487 __tmp.put_f32_le(self.xgyro);
26488 __tmp.put_f32_le(self.ygyro);
26489 __tmp.put_f32_le(self.zgyro);
26490 __tmp.put_f32_le(self.lat);
26491 __tmp.put_f32_le(self.lon);
26492 __tmp.put_f32_le(self.alt);
26493 __tmp.put_f32_le(self.std_dev_horz);
26494 __tmp.put_f32_le(self.std_dev_vert);
26495 __tmp.put_f32_le(self.vn);
26496 __tmp.put_f32_le(self.ve);
26497 __tmp.put_f32_le(self.vd);
26498 __tmp.put_i32_le(self.lat_int);
26499 __tmp.put_i32_le(self.lon_int);
26500 if matches!(version, MavlinkVersion::V2) {
26501 let len = __tmp.len();
26502 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26503 } else {
26504 __tmp.len()
26505 }
26506 }
26507}
26508#[doc = "id: 336"]
26509#[doc = "Configure cellular modems. This message is re-emitted as an acknowledgement by the modem. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
26510#[derive(Debug, Clone, PartialEq)]
26511#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26512#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26513pub struct CELLULAR_CONFIG_DATA {
26514 #[doc = "Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
26515 pub enable_lte: u8,
26516 #[doc = "Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
26517 pub enable_pin: u8,
26518 #[doc = "PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response."]
26519 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26520 pub pin: [u8; 16],
26521 #[doc = "New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response."]
26522 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26523 pub new_pin: [u8; 16],
26524 #[doc = "Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response."]
26525 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26526 pub apn: [u8; 32],
26527 #[doc = "Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response."]
26528 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26529 pub puk: [u8; 16],
26530 #[doc = "Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
26531 pub roaming: u8,
26532 #[doc = "Message acceptance response (sent back to GS)."]
26533 pub response: CellularConfigResponse,
26534}
26535impl CELLULAR_CONFIG_DATA {
26536 pub const ENCODED_LEN: usize = 84usize;
26537 pub const DEFAULT: Self = Self {
26538 enable_lte: 0_u8,
26539 enable_pin: 0_u8,
26540 pin: [0_u8; 16usize],
26541 new_pin: [0_u8; 16usize],
26542 apn: [0_u8; 32usize],
26543 puk: [0_u8; 16usize],
26544 roaming: 0_u8,
26545 response: CellularConfigResponse::DEFAULT,
26546 };
26547 #[cfg(feature = "arbitrary")]
26548 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26549 use arbitrary::{Arbitrary, Unstructured};
26550 let mut buf = [0u8; 1024];
26551 rng.fill_bytes(&mut buf);
26552 let mut unstructured = Unstructured::new(&buf);
26553 Self::arbitrary(&mut unstructured).unwrap_or_default()
26554 }
26555}
26556impl Default for CELLULAR_CONFIG_DATA {
26557 fn default() -> Self {
26558 Self::DEFAULT.clone()
26559 }
26560}
26561impl MessageData for CELLULAR_CONFIG_DATA {
26562 type Message = MavMessage;
26563 const ID: u32 = 336u32;
26564 const NAME: &'static str = "CELLULAR_CONFIG";
26565 const EXTRA_CRC: u8 = 245u8;
26566 const ENCODED_LEN: usize = 84usize;
26567 fn deser(
26568 _version: MavlinkVersion,
26569 __input: &[u8],
26570 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26571 let avail_len = __input.len();
26572 let mut payload_buf = [0; Self::ENCODED_LEN];
26573 let mut buf = if avail_len < Self::ENCODED_LEN {
26574 payload_buf[0..avail_len].copy_from_slice(__input);
26575 Bytes::new(&payload_buf)
26576 } else {
26577 Bytes::new(__input)
26578 };
26579 let mut __struct = Self::default();
26580 __struct.enable_lte = buf.get_u8();
26581 __struct.enable_pin = buf.get_u8();
26582 for v in &mut __struct.pin {
26583 let val = buf.get_u8();
26584 *v = val;
26585 }
26586 for v in &mut __struct.new_pin {
26587 let val = buf.get_u8();
26588 *v = val;
26589 }
26590 for v in &mut __struct.apn {
26591 let val = buf.get_u8();
26592 *v = val;
26593 }
26594 for v in &mut __struct.puk {
26595 let val = buf.get_u8();
26596 *v = val;
26597 }
26598 __struct.roaming = buf.get_u8();
26599 let tmp = buf.get_u8();
26600 __struct.response =
26601 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26602 enum_type: "CellularConfigResponse",
26603 value: tmp as u32,
26604 })?;
26605 Ok(__struct)
26606 }
26607 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26608 let mut __tmp = BytesMut::new(bytes);
26609 #[allow(clippy::absurd_extreme_comparisons)]
26610 #[allow(unused_comparisons)]
26611 if __tmp.remaining() < Self::ENCODED_LEN {
26612 panic!(
26613 "buffer is too small (need {} bytes, but got {})",
26614 Self::ENCODED_LEN,
26615 __tmp.remaining(),
26616 )
26617 }
26618 __tmp.put_u8(self.enable_lte);
26619 __tmp.put_u8(self.enable_pin);
26620 for val in &self.pin {
26621 __tmp.put_u8(*val);
26622 }
26623 for val in &self.new_pin {
26624 __tmp.put_u8(*val);
26625 }
26626 for val in &self.apn {
26627 __tmp.put_u8(*val);
26628 }
26629 for val in &self.puk {
26630 __tmp.put_u8(*val);
26631 }
26632 __tmp.put_u8(self.roaming);
26633 __tmp.put_u8(self.response as u8);
26634 if matches!(version, MavlinkVersion::V2) {
26635 let len = __tmp.len();
26636 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26637 } else {
26638 __tmp.len()
26639 }
26640 }
26641}
26642#[doc = "id: 32"]
26643#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
26644#[derive(Debug, Clone, PartialEq)]
26645#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26646#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26647pub struct LOCAL_POSITION_NED_DATA {
26648 #[doc = "Timestamp (time since system boot)."]
26649 pub time_boot_ms: u32,
26650 #[doc = "X Position"]
26651 pub x: f32,
26652 #[doc = "Y Position"]
26653 pub y: f32,
26654 #[doc = "Z Position"]
26655 pub z: f32,
26656 #[doc = "X Speed"]
26657 pub vx: f32,
26658 #[doc = "Y Speed"]
26659 pub vy: f32,
26660 #[doc = "Z Speed"]
26661 pub vz: f32,
26662}
26663impl LOCAL_POSITION_NED_DATA {
26664 pub const ENCODED_LEN: usize = 28usize;
26665 pub const DEFAULT: Self = Self {
26666 time_boot_ms: 0_u32,
26667 x: 0.0_f32,
26668 y: 0.0_f32,
26669 z: 0.0_f32,
26670 vx: 0.0_f32,
26671 vy: 0.0_f32,
26672 vz: 0.0_f32,
26673 };
26674 #[cfg(feature = "arbitrary")]
26675 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26676 use arbitrary::{Arbitrary, Unstructured};
26677 let mut buf = [0u8; 1024];
26678 rng.fill_bytes(&mut buf);
26679 let mut unstructured = Unstructured::new(&buf);
26680 Self::arbitrary(&mut unstructured).unwrap_or_default()
26681 }
26682}
26683impl Default for LOCAL_POSITION_NED_DATA {
26684 fn default() -> Self {
26685 Self::DEFAULT.clone()
26686 }
26687}
26688impl MessageData for LOCAL_POSITION_NED_DATA {
26689 type Message = MavMessage;
26690 const ID: u32 = 32u32;
26691 const NAME: &'static str = "LOCAL_POSITION_NED";
26692 const EXTRA_CRC: u8 = 185u8;
26693 const ENCODED_LEN: usize = 28usize;
26694 fn deser(
26695 _version: MavlinkVersion,
26696 __input: &[u8],
26697 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26698 let avail_len = __input.len();
26699 let mut payload_buf = [0; Self::ENCODED_LEN];
26700 let mut buf = if avail_len < Self::ENCODED_LEN {
26701 payload_buf[0..avail_len].copy_from_slice(__input);
26702 Bytes::new(&payload_buf)
26703 } else {
26704 Bytes::new(__input)
26705 };
26706 let mut __struct = Self::default();
26707 __struct.time_boot_ms = buf.get_u32_le();
26708 __struct.x = buf.get_f32_le();
26709 __struct.y = buf.get_f32_le();
26710 __struct.z = buf.get_f32_le();
26711 __struct.vx = buf.get_f32_le();
26712 __struct.vy = buf.get_f32_le();
26713 __struct.vz = buf.get_f32_le();
26714 Ok(__struct)
26715 }
26716 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26717 let mut __tmp = BytesMut::new(bytes);
26718 #[allow(clippy::absurd_extreme_comparisons)]
26719 #[allow(unused_comparisons)]
26720 if __tmp.remaining() < Self::ENCODED_LEN {
26721 panic!(
26722 "buffer is too small (need {} bytes, but got {})",
26723 Self::ENCODED_LEN,
26724 __tmp.remaining(),
26725 )
26726 }
26727 __tmp.put_u32_le(self.time_boot_ms);
26728 __tmp.put_f32_le(self.x);
26729 __tmp.put_f32_le(self.y);
26730 __tmp.put_f32_le(self.z);
26731 __tmp.put_f32_le(self.vx);
26732 __tmp.put_f32_le(self.vy);
26733 __tmp.put_f32_le(self.vz);
26734 if matches!(version, MavlinkVersion::V2) {
26735 let len = __tmp.len();
26736 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26737 } else {
26738 __tmp.len()
26739 }
26740 }
26741}
26742#[doc = "id: 275"]
26743#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
26744#[derive(Debug, Clone, PartialEq)]
26745#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26746#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26747pub struct CAMERA_TRACKING_IMAGE_STATUS_DATA {
26748 #[doc = "Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
26749 pub point_x: f32,
26750 #[doc = "Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
26751 pub point_y: f32,
26752 #[doc = "Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown"]
26753 pub radius: f32,
26754 #[doc = "Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
26755 pub rec_top_x: f32,
26756 #[doc = "Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
26757 pub rec_top_y: f32,
26758 #[doc = "Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
26759 pub rec_bottom_x: f32,
26760 #[doc = "Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
26761 pub rec_bottom_y: f32,
26762 #[doc = "Current tracking status"]
26763 pub tracking_status: CameraTrackingStatusFlags,
26764 #[doc = "Current tracking mode"]
26765 pub tracking_mode: CameraTrackingMode,
26766 #[doc = "Defines location of target data"]
26767 pub target_data: CameraTrackingTargetData,
26768 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
26769 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26770 pub camera_device_id: u8,
26771}
26772impl CAMERA_TRACKING_IMAGE_STATUS_DATA {
26773 pub const ENCODED_LEN: usize = 32usize;
26774 pub const DEFAULT: Self = Self {
26775 point_x: 0.0_f32,
26776 point_y: 0.0_f32,
26777 radius: 0.0_f32,
26778 rec_top_x: 0.0_f32,
26779 rec_top_y: 0.0_f32,
26780 rec_bottom_x: 0.0_f32,
26781 rec_bottom_y: 0.0_f32,
26782 tracking_status: CameraTrackingStatusFlags::DEFAULT,
26783 tracking_mode: CameraTrackingMode::DEFAULT,
26784 target_data: CameraTrackingTargetData::DEFAULT,
26785 camera_device_id: 0_u8,
26786 };
26787 #[cfg(feature = "arbitrary")]
26788 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26789 use arbitrary::{Arbitrary, Unstructured};
26790 let mut buf = [0u8; 1024];
26791 rng.fill_bytes(&mut buf);
26792 let mut unstructured = Unstructured::new(&buf);
26793 Self::arbitrary(&mut unstructured).unwrap_or_default()
26794 }
26795}
26796impl Default for CAMERA_TRACKING_IMAGE_STATUS_DATA {
26797 fn default() -> Self {
26798 Self::DEFAULT.clone()
26799 }
26800}
26801impl MessageData for CAMERA_TRACKING_IMAGE_STATUS_DATA {
26802 type Message = MavMessage;
26803 const ID: u32 = 275u32;
26804 const NAME: &'static str = "CAMERA_TRACKING_IMAGE_STATUS";
26805 const EXTRA_CRC: u8 = 126u8;
26806 const ENCODED_LEN: usize = 32usize;
26807 fn deser(
26808 _version: MavlinkVersion,
26809 __input: &[u8],
26810 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26811 let avail_len = __input.len();
26812 let mut payload_buf = [0; Self::ENCODED_LEN];
26813 let mut buf = if avail_len < Self::ENCODED_LEN {
26814 payload_buf[0..avail_len].copy_from_slice(__input);
26815 Bytes::new(&payload_buf)
26816 } else {
26817 Bytes::new(__input)
26818 };
26819 let mut __struct = Self::default();
26820 __struct.point_x = buf.get_f32_le();
26821 __struct.point_y = buf.get_f32_le();
26822 __struct.radius = buf.get_f32_le();
26823 __struct.rec_top_x = buf.get_f32_le();
26824 __struct.rec_top_y = buf.get_f32_le();
26825 __struct.rec_bottom_x = buf.get_f32_le();
26826 __struct.rec_bottom_y = buf.get_f32_le();
26827 let tmp = buf.get_u8();
26828 __struct.tracking_status =
26829 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26830 enum_type: "CameraTrackingStatusFlags",
26831 value: tmp as u32,
26832 })?;
26833 let tmp = buf.get_u8();
26834 __struct.tracking_mode =
26835 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26836 enum_type: "CameraTrackingMode",
26837 value: tmp as u32,
26838 })?;
26839 let tmp = buf.get_u8();
26840 __struct.target_data =
26841 CameraTrackingTargetData::from_bits(tmp & CameraTrackingTargetData::all().bits())
26842 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
26843 flag_type: "CameraTrackingTargetData",
26844 value: tmp as u32,
26845 })?;
26846 __struct.camera_device_id = buf.get_u8();
26847 Ok(__struct)
26848 }
26849 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26850 let mut __tmp = BytesMut::new(bytes);
26851 #[allow(clippy::absurd_extreme_comparisons)]
26852 #[allow(unused_comparisons)]
26853 if __tmp.remaining() < Self::ENCODED_LEN {
26854 panic!(
26855 "buffer is too small (need {} bytes, but got {})",
26856 Self::ENCODED_LEN,
26857 __tmp.remaining(),
26858 )
26859 }
26860 __tmp.put_f32_le(self.point_x);
26861 __tmp.put_f32_le(self.point_y);
26862 __tmp.put_f32_le(self.radius);
26863 __tmp.put_f32_le(self.rec_top_x);
26864 __tmp.put_f32_le(self.rec_top_y);
26865 __tmp.put_f32_le(self.rec_bottom_x);
26866 __tmp.put_f32_le(self.rec_bottom_y);
26867 __tmp.put_u8(self.tracking_status as u8);
26868 __tmp.put_u8(self.tracking_mode as u8);
26869 __tmp.put_u8(self.target_data.bits());
26870 __tmp.put_u8(self.camera_device_id);
26871 if matches!(version, MavlinkVersion::V2) {
26872 let len = __tmp.len();
26873 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26874 } else {
26875 __tmp.len()
26876 }
26877 }
26878}
26879#[doc = "id: 385"]
26880#[doc = "Message for transporting \"arbitrary\" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification."]
26881#[derive(Debug, Clone, PartialEq)]
26882#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26883#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26884pub struct TUNNEL_DATA {
26885 #[doc = "A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
26886 pub payload_type: MavTunnelPayloadType,
26887 #[doc = "System ID (can be 0 for broadcast, but this is discouraged)"]
26888 pub target_system: u8,
26889 #[doc = "Component ID (can be 0 for broadcast, but this is discouraged)"]
26890 pub target_component: u8,
26891 #[doc = "Length of the data transported in payload"]
26892 pub payload_length: u8,
26893 #[doc = "Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type."]
26894 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26895 pub payload: [u8; 128],
26896}
26897impl TUNNEL_DATA {
26898 pub const ENCODED_LEN: usize = 133usize;
26899 pub const DEFAULT: Self = Self {
26900 payload_type: MavTunnelPayloadType::DEFAULT,
26901 target_system: 0_u8,
26902 target_component: 0_u8,
26903 payload_length: 0_u8,
26904 payload: [0_u8; 128usize],
26905 };
26906 #[cfg(feature = "arbitrary")]
26907 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26908 use arbitrary::{Arbitrary, Unstructured};
26909 let mut buf = [0u8; 1024];
26910 rng.fill_bytes(&mut buf);
26911 let mut unstructured = Unstructured::new(&buf);
26912 Self::arbitrary(&mut unstructured).unwrap_or_default()
26913 }
26914}
26915impl Default for TUNNEL_DATA {
26916 fn default() -> Self {
26917 Self::DEFAULT.clone()
26918 }
26919}
26920impl MessageData for TUNNEL_DATA {
26921 type Message = MavMessage;
26922 const ID: u32 = 385u32;
26923 const NAME: &'static str = "TUNNEL";
26924 const EXTRA_CRC: u8 = 147u8;
26925 const ENCODED_LEN: usize = 133usize;
26926 fn deser(
26927 _version: MavlinkVersion,
26928 __input: &[u8],
26929 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26930 let avail_len = __input.len();
26931 let mut payload_buf = [0; Self::ENCODED_LEN];
26932 let mut buf = if avail_len < Self::ENCODED_LEN {
26933 payload_buf[0..avail_len].copy_from_slice(__input);
26934 Bytes::new(&payload_buf)
26935 } else {
26936 Bytes::new(__input)
26937 };
26938 let mut __struct = Self::default();
26939 let tmp = buf.get_u16_le();
26940 __struct.payload_type = FromPrimitive::from_u16(tmp).ok_or(
26941 ::mavlink_core::error::ParserError::InvalidEnum {
26942 enum_type: "MavTunnelPayloadType",
26943 value: tmp as u32,
26944 },
26945 )?;
26946 __struct.target_system = buf.get_u8();
26947 __struct.target_component = buf.get_u8();
26948 __struct.payload_length = buf.get_u8();
26949 for v in &mut __struct.payload {
26950 let val = buf.get_u8();
26951 *v = val;
26952 }
26953 Ok(__struct)
26954 }
26955 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26956 let mut __tmp = BytesMut::new(bytes);
26957 #[allow(clippy::absurd_extreme_comparisons)]
26958 #[allow(unused_comparisons)]
26959 if __tmp.remaining() < Self::ENCODED_LEN {
26960 panic!(
26961 "buffer is too small (need {} bytes, but got {})",
26962 Self::ENCODED_LEN,
26963 __tmp.remaining(),
26964 )
26965 }
26966 __tmp.put_u16_le(self.payload_type as u16);
26967 __tmp.put_u8(self.target_system);
26968 __tmp.put_u8(self.target_component);
26969 __tmp.put_u8(self.payload_length);
26970 for val in &self.payload {
26971 __tmp.put_u8(*val);
26972 }
26973 if matches!(version, MavlinkVersion::V2) {
26974 let len = __tmp.len();
26975 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26976 } else {
26977 __tmp.len()
26978 }
26979 }
26980}
26981#[doc = "id: 65"]
26982#[doc = "The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
26983#[derive(Debug, Clone, PartialEq)]
26984#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26985#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26986pub struct RC_CHANNELS_DATA {
26987 #[doc = "Timestamp (time since system boot)."]
26988 pub time_boot_ms: u32,
26989 #[doc = "RC channel 1 value."]
26990 pub chan1_raw: u16,
26991 #[doc = "RC channel 2 value."]
26992 pub chan2_raw: u16,
26993 #[doc = "RC channel 3 value."]
26994 pub chan3_raw: u16,
26995 #[doc = "RC channel 4 value."]
26996 pub chan4_raw: u16,
26997 #[doc = "RC channel 5 value."]
26998 pub chan5_raw: u16,
26999 #[doc = "RC channel 6 value."]
27000 pub chan6_raw: u16,
27001 #[doc = "RC channel 7 value."]
27002 pub chan7_raw: u16,
27003 #[doc = "RC channel 8 value."]
27004 pub chan8_raw: u16,
27005 #[doc = "RC channel 9 value."]
27006 pub chan9_raw: u16,
27007 #[doc = "RC channel 10 value."]
27008 pub chan10_raw: u16,
27009 #[doc = "RC channel 11 value."]
27010 pub chan11_raw: u16,
27011 #[doc = "RC channel 12 value."]
27012 pub chan12_raw: u16,
27013 #[doc = "RC channel 13 value."]
27014 pub chan13_raw: u16,
27015 #[doc = "RC channel 14 value."]
27016 pub chan14_raw: u16,
27017 #[doc = "RC channel 15 value."]
27018 pub chan15_raw: u16,
27019 #[doc = "RC channel 16 value."]
27020 pub chan16_raw: u16,
27021 #[doc = "RC channel 17 value."]
27022 pub chan17_raw: u16,
27023 #[doc = "RC channel 18 value."]
27024 pub chan18_raw: u16,
27025 #[doc = "Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available."]
27026 pub chancount: u8,
27027 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
27028 pub rssi: u8,
27029}
27030impl RC_CHANNELS_DATA {
27031 pub const ENCODED_LEN: usize = 42usize;
27032 pub const DEFAULT: Self = Self {
27033 time_boot_ms: 0_u32,
27034 chan1_raw: 0_u16,
27035 chan2_raw: 0_u16,
27036 chan3_raw: 0_u16,
27037 chan4_raw: 0_u16,
27038 chan5_raw: 0_u16,
27039 chan6_raw: 0_u16,
27040 chan7_raw: 0_u16,
27041 chan8_raw: 0_u16,
27042 chan9_raw: 0_u16,
27043 chan10_raw: 0_u16,
27044 chan11_raw: 0_u16,
27045 chan12_raw: 0_u16,
27046 chan13_raw: 0_u16,
27047 chan14_raw: 0_u16,
27048 chan15_raw: 0_u16,
27049 chan16_raw: 0_u16,
27050 chan17_raw: 0_u16,
27051 chan18_raw: 0_u16,
27052 chancount: 0_u8,
27053 rssi: 0_u8,
27054 };
27055 #[cfg(feature = "arbitrary")]
27056 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27057 use arbitrary::{Arbitrary, Unstructured};
27058 let mut buf = [0u8; 1024];
27059 rng.fill_bytes(&mut buf);
27060 let mut unstructured = Unstructured::new(&buf);
27061 Self::arbitrary(&mut unstructured).unwrap_or_default()
27062 }
27063}
27064impl Default for RC_CHANNELS_DATA {
27065 fn default() -> Self {
27066 Self::DEFAULT.clone()
27067 }
27068}
27069impl MessageData for RC_CHANNELS_DATA {
27070 type Message = MavMessage;
27071 const ID: u32 = 65u32;
27072 const NAME: &'static str = "RC_CHANNELS";
27073 const EXTRA_CRC: u8 = 118u8;
27074 const ENCODED_LEN: usize = 42usize;
27075 fn deser(
27076 _version: MavlinkVersion,
27077 __input: &[u8],
27078 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27079 let avail_len = __input.len();
27080 let mut payload_buf = [0; Self::ENCODED_LEN];
27081 let mut buf = if avail_len < Self::ENCODED_LEN {
27082 payload_buf[0..avail_len].copy_from_slice(__input);
27083 Bytes::new(&payload_buf)
27084 } else {
27085 Bytes::new(__input)
27086 };
27087 let mut __struct = Self::default();
27088 __struct.time_boot_ms = buf.get_u32_le();
27089 __struct.chan1_raw = buf.get_u16_le();
27090 __struct.chan2_raw = buf.get_u16_le();
27091 __struct.chan3_raw = buf.get_u16_le();
27092 __struct.chan4_raw = buf.get_u16_le();
27093 __struct.chan5_raw = buf.get_u16_le();
27094 __struct.chan6_raw = buf.get_u16_le();
27095 __struct.chan7_raw = buf.get_u16_le();
27096 __struct.chan8_raw = buf.get_u16_le();
27097 __struct.chan9_raw = buf.get_u16_le();
27098 __struct.chan10_raw = buf.get_u16_le();
27099 __struct.chan11_raw = buf.get_u16_le();
27100 __struct.chan12_raw = buf.get_u16_le();
27101 __struct.chan13_raw = buf.get_u16_le();
27102 __struct.chan14_raw = buf.get_u16_le();
27103 __struct.chan15_raw = buf.get_u16_le();
27104 __struct.chan16_raw = buf.get_u16_le();
27105 __struct.chan17_raw = buf.get_u16_le();
27106 __struct.chan18_raw = buf.get_u16_le();
27107 __struct.chancount = buf.get_u8();
27108 __struct.rssi = buf.get_u8();
27109 Ok(__struct)
27110 }
27111 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27112 let mut __tmp = BytesMut::new(bytes);
27113 #[allow(clippy::absurd_extreme_comparisons)]
27114 #[allow(unused_comparisons)]
27115 if __tmp.remaining() < Self::ENCODED_LEN {
27116 panic!(
27117 "buffer is too small (need {} bytes, but got {})",
27118 Self::ENCODED_LEN,
27119 __tmp.remaining(),
27120 )
27121 }
27122 __tmp.put_u32_le(self.time_boot_ms);
27123 __tmp.put_u16_le(self.chan1_raw);
27124 __tmp.put_u16_le(self.chan2_raw);
27125 __tmp.put_u16_le(self.chan3_raw);
27126 __tmp.put_u16_le(self.chan4_raw);
27127 __tmp.put_u16_le(self.chan5_raw);
27128 __tmp.put_u16_le(self.chan6_raw);
27129 __tmp.put_u16_le(self.chan7_raw);
27130 __tmp.put_u16_le(self.chan8_raw);
27131 __tmp.put_u16_le(self.chan9_raw);
27132 __tmp.put_u16_le(self.chan10_raw);
27133 __tmp.put_u16_le(self.chan11_raw);
27134 __tmp.put_u16_le(self.chan12_raw);
27135 __tmp.put_u16_le(self.chan13_raw);
27136 __tmp.put_u16_le(self.chan14_raw);
27137 __tmp.put_u16_le(self.chan15_raw);
27138 __tmp.put_u16_le(self.chan16_raw);
27139 __tmp.put_u16_le(self.chan17_raw);
27140 __tmp.put_u16_le(self.chan18_raw);
27141 __tmp.put_u8(self.chancount);
27142 __tmp.put_u8(self.rssi);
27143 if matches!(version, MavlinkVersion::V2) {
27144 let len = __tmp.len();
27145 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27146 } else {
27147 __tmp.len()
27148 }
27149 }
27150}
27151#[doc = "id: 251"]
27152#[doc = "Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
27153#[derive(Debug, Clone, PartialEq)]
27154#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27155#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27156pub struct NAMED_VALUE_FLOAT_DATA {
27157 #[doc = "Timestamp (time since system boot)."]
27158 pub time_boot_ms: u32,
27159 #[doc = "Floating point value"]
27160 pub value: f32,
27161 #[doc = "Name of the debug variable"]
27162 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27163 pub name: [u8; 10],
27164}
27165impl NAMED_VALUE_FLOAT_DATA {
27166 pub const ENCODED_LEN: usize = 18usize;
27167 pub const DEFAULT: Self = Self {
27168 time_boot_ms: 0_u32,
27169 value: 0.0_f32,
27170 name: [0_u8; 10usize],
27171 };
27172 #[cfg(feature = "arbitrary")]
27173 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27174 use arbitrary::{Arbitrary, Unstructured};
27175 let mut buf = [0u8; 1024];
27176 rng.fill_bytes(&mut buf);
27177 let mut unstructured = Unstructured::new(&buf);
27178 Self::arbitrary(&mut unstructured).unwrap_or_default()
27179 }
27180}
27181impl Default for NAMED_VALUE_FLOAT_DATA {
27182 fn default() -> Self {
27183 Self::DEFAULT.clone()
27184 }
27185}
27186impl MessageData for NAMED_VALUE_FLOAT_DATA {
27187 type Message = MavMessage;
27188 const ID: u32 = 251u32;
27189 const NAME: &'static str = "NAMED_VALUE_FLOAT";
27190 const EXTRA_CRC: u8 = 170u8;
27191 const ENCODED_LEN: usize = 18usize;
27192 fn deser(
27193 _version: MavlinkVersion,
27194 __input: &[u8],
27195 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27196 let avail_len = __input.len();
27197 let mut payload_buf = [0; Self::ENCODED_LEN];
27198 let mut buf = if avail_len < Self::ENCODED_LEN {
27199 payload_buf[0..avail_len].copy_from_slice(__input);
27200 Bytes::new(&payload_buf)
27201 } else {
27202 Bytes::new(__input)
27203 };
27204 let mut __struct = Self::default();
27205 __struct.time_boot_ms = buf.get_u32_le();
27206 __struct.value = buf.get_f32_le();
27207 for v in &mut __struct.name {
27208 let val = buf.get_u8();
27209 *v = val;
27210 }
27211 Ok(__struct)
27212 }
27213 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27214 let mut __tmp = BytesMut::new(bytes);
27215 #[allow(clippy::absurd_extreme_comparisons)]
27216 #[allow(unused_comparisons)]
27217 if __tmp.remaining() < Self::ENCODED_LEN {
27218 panic!(
27219 "buffer is too small (need {} bytes, but got {})",
27220 Self::ENCODED_LEN,
27221 __tmp.remaining(),
27222 )
27223 }
27224 __tmp.put_u32_le(self.time_boot_ms);
27225 __tmp.put_f32_le(self.value);
27226 for val in &self.name {
27227 __tmp.put_u8(*val);
27228 }
27229 if matches!(version, MavlinkVersion::V2) {
27230 let len = __tmp.len();
27231 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27232 } else {
27233 __tmp.len()
27234 }
27235 }
27236}
27237#[doc = "id: 139"]
27238#[doc = "Set the vehicle attitude and body angular rates."]
27239#[derive(Debug, Clone, PartialEq)]
27240#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27241#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27242pub struct SET_ACTUATOR_CONTROL_TARGET_DATA {
27243 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27244 pub time_usec: u64,
27245 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
27246 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27247 pub controls: [f32; 8],
27248 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
27249 pub group_mlx: u8,
27250 #[doc = "System ID"]
27251 pub target_system: u8,
27252 #[doc = "Component ID"]
27253 pub target_component: u8,
27254}
27255impl SET_ACTUATOR_CONTROL_TARGET_DATA {
27256 pub const ENCODED_LEN: usize = 43usize;
27257 pub const DEFAULT: Self = Self {
27258 time_usec: 0_u64,
27259 controls: [0.0_f32; 8usize],
27260 group_mlx: 0_u8,
27261 target_system: 0_u8,
27262 target_component: 0_u8,
27263 };
27264 #[cfg(feature = "arbitrary")]
27265 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27266 use arbitrary::{Arbitrary, Unstructured};
27267 let mut buf = [0u8; 1024];
27268 rng.fill_bytes(&mut buf);
27269 let mut unstructured = Unstructured::new(&buf);
27270 Self::arbitrary(&mut unstructured).unwrap_or_default()
27271 }
27272}
27273impl Default for SET_ACTUATOR_CONTROL_TARGET_DATA {
27274 fn default() -> Self {
27275 Self::DEFAULT.clone()
27276 }
27277}
27278impl MessageData for SET_ACTUATOR_CONTROL_TARGET_DATA {
27279 type Message = MavMessage;
27280 const ID: u32 = 139u32;
27281 const NAME: &'static str = "SET_ACTUATOR_CONTROL_TARGET";
27282 const EXTRA_CRC: u8 = 168u8;
27283 const ENCODED_LEN: usize = 43usize;
27284 fn deser(
27285 _version: MavlinkVersion,
27286 __input: &[u8],
27287 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27288 let avail_len = __input.len();
27289 let mut payload_buf = [0; Self::ENCODED_LEN];
27290 let mut buf = if avail_len < Self::ENCODED_LEN {
27291 payload_buf[0..avail_len].copy_from_slice(__input);
27292 Bytes::new(&payload_buf)
27293 } else {
27294 Bytes::new(__input)
27295 };
27296 let mut __struct = Self::default();
27297 __struct.time_usec = buf.get_u64_le();
27298 for v in &mut __struct.controls {
27299 let val = buf.get_f32_le();
27300 *v = val;
27301 }
27302 __struct.group_mlx = buf.get_u8();
27303 __struct.target_system = buf.get_u8();
27304 __struct.target_component = buf.get_u8();
27305 Ok(__struct)
27306 }
27307 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27308 let mut __tmp = BytesMut::new(bytes);
27309 #[allow(clippy::absurd_extreme_comparisons)]
27310 #[allow(unused_comparisons)]
27311 if __tmp.remaining() < Self::ENCODED_LEN {
27312 panic!(
27313 "buffer is too small (need {} bytes, but got {})",
27314 Self::ENCODED_LEN,
27315 __tmp.remaining(),
27316 )
27317 }
27318 __tmp.put_u64_le(self.time_usec);
27319 for val in &self.controls {
27320 __tmp.put_f32_le(*val);
27321 }
27322 __tmp.put_u8(self.group_mlx);
27323 __tmp.put_u8(self.target_system);
27324 __tmp.put_u8(self.target_component);
27325 if matches!(version, MavlinkVersion::V2) {
27326 let len = __tmp.len();
27327 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27328 } else {
27329 __tmp.len()
27330 }
27331 }
27332}
27333#[doc = "id: 85"]
27334#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way."]
27335#[derive(Debug, Clone, PartialEq)]
27336#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27337#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27338pub struct POSITION_TARGET_LOCAL_NED_DATA {
27339 #[doc = "Timestamp (time since system boot)."]
27340 pub time_boot_ms: u32,
27341 #[doc = "X Position in NED frame"]
27342 pub x: f32,
27343 #[doc = "Y Position in NED frame"]
27344 pub y: f32,
27345 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
27346 pub z: f32,
27347 #[doc = "X velocity in NED frame"]
27348 pub vx: f32,
27349 #[doc = "Y velocity in NED frame"]
27350 pub vy: f32,
27351 #[doc = "Z velocity in NED frame"]
27352 pub vz: f32,
27353 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27354 pub afx: f32,
27355 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27356 pub afy: f32,
27357 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27358 pub afz: f32,
27359 #[doc = "yaw setpoint"]
27360 pub yaw: f32,
27361 #[doc = "yaw rate setpoint"]
27362 pub yaw_rate: f32,
27363 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
27364 pub type_mask: PositionTargetTypemask,
27365 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
27366 pub coordinate_frame: MavFrame,
27367}
27368impl POSITION_TARGET_LOCAL_NED_DATA {
27369 pub const ENCODED_LEN: usize = 51usize;
27370 pub const DEFAULT: Self = Self {
27371 time_boot_ms: 0_u32,
27372 x: 0.0_f32,
27373 y: 0.0_f32,
27374 z: 0.0_f32,
27375 vx: 0.0_f32,
27376 vy: 0.0_f32,
27377 vz: 0.0_f32,
27378 afx: 0.0_f32,
27379 afy: 0.0_f32,
27380 afz: 0.0_f32,
27381 yaw: 0.0_f32,
27382 yaw_rate: 0.0_f32,
27383 type_mask: PositionTargetTypemask::DEFAULT,
27384 coordinate_frame: MavFrame::DEFAULT,
27385 };
27386 #[cfg(feature = "arbitrary")]
27387 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27388 use arbitrary::{Arbitrary, Unstructured};
27389 let mut buf = [0u8; 1024];
27390 rng.fill_bytes(&mut buf);
27391 let mut unstructured = Unstructured::new(&buf);
27392 Self::arbitrary(&mut unstructured).unwrap_or_default()
27393 }
27394}
27395impl Default for POSITION_TARGET_LOCAL_NED_DATA {
27396 fn default() -> Self {
27397 Self::DEFAULT.clone()
27398 }
27399}
27400impl MessageData for POSITION_TARGET_LOCAL_NED_DATA {
27401 type Message = MavMessage;
27402 const ID: u32 = 85u32;
27403 const NAME: &'static str = "POSITION_TARGET_LOCAL_NED";
27404 const EXTRA_CRC: u8 = 140u8;
27405 const ENCODED_LEN: usize = 51usize;
27406 fn deser(
27407 _version: MavlinkVersion,
27408 __input: &[u8],
27409 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27410 let avail_len = __input.len();
27411 let mut payload_buf = [0; Self::ENCODED_LEN];
27412 let mut buf = if avail_len < Self::ENCODED_LEN {
27413 payload_buf[0..avail_len].copy_from_slice(__input);
27414 Bytes::new(&payload_buf)
27415 } else {
27416 Bytes::new(__input)
27417 };
27418 let mut __struct = Self::default();
27419 __struct.time_boot_ms = buf.get_u32_le();
27420 __struct.x = buf.get_f32_le();
27421 __struct.y = buf.get_f32_le();
27422 __struct.z = buf.get_f32_le();
27423 __struct.vx = buf.get_f32_le();
27424 __struct.vy = buf.get_f32_le();
27425 __struct.vz = buf.get_f32_le();
27426 __struct.afx = buf.get_f32_le();
27427 __struct.afy = buf.get_f32_le();
27428 __struct.afz = buf.get_f32_le();
27429 __struct.yaw = buf.get_f32_le();
27430 __struct.yaw_rate = buf.get_f32_le();
27431 let tmp = buf.get_u16_le();
27432 __struct.type_mask = PositionTargetTypemask::from_bits(
27433 tmp & PositionTargetTypemask::all().bits(),
27434 )
27435 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
27436 flag_type: "PositionTargetTypemask",
27437 value: tmp as u32,
27438 })?;
27439 let tmp = buf.get_u8();
27440 __struct.coordinate_frame =
27441 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27442 enum_type: "MavFrame",
27443 value: tmp as u32,
27444 })?;
27445 Ok(__struct)
27446 }
27447 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27448 let mut __tmp = BytesMut::new(bytes);
27449 #[allow(clippy::absurd_extreme_comparisons)]
27450 #[allow(unused_comparisons)]
27451 if __tmp.remaining() < Self::ENCODED_LEN {
27452 panic!(
27453 "buffer is too small (need {} bytes, but got {})",
27454 Self::ENCODED_LEN,
27455 __tmp.remaining(),
27456 )
27457 }
27458 __tmp.put_u32_le(self.time_boot_ms);
27459 __tmp.put_f32_le(self.x);
27460 __tmp.put_f32_le(self.y);
27461 __tmp.put_f32_le(self.z);
27462 __tmp.put_f32_le(self.vx);
27463 __tmp.put_f32_le(self.vy);
27464 __tmp.put_f32_le(self.vz);
27465 __tmp.put_f32_le(self.afx);
27466 __tmp.put_f32_le(self.afy);
27467 __tmp.put_f32_le(self.afz);
27468 __tmp.put_f32_le(self.yaw);
27469 __tmp.put_f32_le(self.yaw_rate);
27470 __tmp.put_u16_le(self.type_mask.bits());
27471 __tmp.put_u8(self.coordinate_frame as u8);
27472 if matches!(version, MavlinkVersion::V2) {
27473 let len = __tmp.len();
27474 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27475 } else {
27476 __tmp.len()
27477 }
27478 }
27479}
27480#[doc = "id: 249"]
27481#[doc = "Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
27482#[derive(Debug, Clone, PartialEq)]
27483#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27484#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27485pub struct MEMORY_VECT_DATA {
27486 #[doc = "Starting address of the debug variables"]
27487 pub address: u16,
27488 #[doc = "Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below"]
27489 pub ver: u8,
27490 #[doc = "Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14"]
27491 pub mavtype: u8,
27492 #[doc = "Memory contents at specified address"]
27493 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27494 pub value: [i8; 32],
27495}
27496impl MEMORY_VECT_DATA {
27497 pub const ENCODED_LEN: usize = 36usize;
27498 pub const DEFAULT: Self = Self {
27499 address: 0_u16,
27500 ver: 0_u8,
27501 mavtype: 0_u8,
27502 value: [0_i8; 32usize],
27503 };
27504 #[cfg(feature = "arbitrary")]
27505 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27506 use arbitrary::{Arbitrary, Unstructured};
27507 let mut buf = [0u8; 1024];
27508 rng.fill_bytes(&mut buf);
27509 let mut unstructured = Unstructured::new(&buf);
27510 Self::arbitrary(&mut unstructured).unwrap_or_default()
27511 }
27512}
27513impl Default for MEMORY_VECT_DATA {
27514 fn default() -> Self {
27515 Self::DEFAULT.clone()
27516 }
27517}
27518impl MessageData for MEMORY_VECT_DATA {
27519 type Message = MavMessage;
27520 const ID: u32 = 249u32;
27521 const NAME: &'static str = "MEMORY_VECT";
27522 const EXTRA_CRC: u8 = 204u8;
27523 const ENCODED_LEN: usize = 36usize;
27524 fn deser(
27525 _version: MavlinkVersion,
27526 __input: &[u8],
27527 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27528 let avail_len = __input.len();
27529 let mut payload_buf = [0; Self::ENCODED_LEN];
27530 let mut buf = if avail_len < Self::ENCODED_LEN {
27531 payload_buf[0..avail_len].copy_from_slice(__input);
27532 Bytes::new(&payload_buf)
27533 } else {
27534 Bytes::new(__input)
27535 };
27536 let mut __struct = Self::default();
27537 __struct.address = buf.get_u16_le();
27538 __struct.ver = buf.get_u8();
27539 __struct.mavtype = buf.get_u8();
27540 for v in &mut __struct.value {
27541 let val = buf.get_i8();
27542 *v = val;
27543 }
27544 Ok(__struct)
27545 }
27546 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27547 let mut __tmp = BytesMut::new(bytes);
27548 #[allow(clippy::absurd_extreme_comparisons)]
27549 #[allow(unused_comparisons)]
27550 if __tmp.remaining() < Self::ENCODED_LEN {
27551 panic!(
27552 "buffer is too small (need {} bytes, but got {})",
27553 Self::ENCODED_LEN,
27554 __tmp.remaining(),
27555 )
27556 }
27557 __tmp.put_u16_le(self.address);
27558 __tmp.put_u8(self.ver);
27559 __tmp.put_u8(self.mavtype);
27560 for val in &self.value {
27561 __tmp.put_i8(*val);
27562 }
27563 if matches!(version, MavlinkVersion::V2) {
27564 let len = __tmp.len();
27565 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27566 } else {
27567 __tmp.len()
27568 }
27569 }
27570}
27571#[doc = "id: 321"]
27572#[doc = "Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE."]
27573#[derive(Debug, Clone, PartialEq)]
27574#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27575#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27576pub struct PARAM_EXT_REQUEST_LIST_DATA {
27577 #[doc = "System ID"]
27578 pub target_system: u8,
27579 #[doc = "Component ID"]
27580 pub target_component: u8,
27581}
27582impl PARAM_EXT_REQUEST_LIST_DATA {
27583 pub const ENCODED_LEN: usize = 2usize;
27584 pub const DEFAULT: Self = Self {
27585 target_system: 0_u8,
27586 target_component: 0_u8,
27587 };
27588 #[cfg(feature = "arbitrary")]
27589 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27590 use arbitrary::{Arbitrary, Unstructured};
27591 let mut buf = [0u8; 1024];
27592 rng.fill_bytes(&mut buf);
27593 let mut unstructured = Unstructured::new(&buf);
27594 Self::arbitrary(&mut unstructured).unwrap_or_default()
27595 }
27596}
27597impl Default for PARAM_EXT_REQUEST_LIST_DATA {
27598 fn default() -> Self {
27599 Self::DEFAULT.clone()
27600 }
27601}
27602impl MessageData for PARAM_EXT_REQUEST_LIST_DATA {
27603 type Message = MavMessage;
27604 const ID: u32 = 321u32;
27605 const NAME: &'static str = "PARAM_EXT_REQUEST_LIST";
27606 const EXTRA_CRC: u8 = 88u8;
27607 const ENCODED_LEN: usize = 2usize;
27608 fn deser(
27609 _version: MavlinkVersion,
27610 __input: &[u8],
27611 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27612 let avail_len = __input.len();
27613 let mut payload_buf = [0; Self::ENCODED_LEN];
27614 let mut buf = if avail_len < Self::ENCODED_LEN {
27615 payload_buf[0..avail_len].copy_from_slice(__input);
27616 Bytes::new(&payload_buf)
27617 } else {
27618 Bytes::new(__input)
27619 };
27620 let mut __struct = Self::default();
27621 __struct.target_system = buf.get_u8();
27622 __struct.target_component = buf.get_u8();
27623 Ok(__struct)
27624 }
27625 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27626 let mut __tmp = BytesMut::new(bytes);
27627 #[allow(clippy::absurd_extreme_comparisons)]
27628 #[allow(unused_comparisons)]
27629 if __tmp.remaining() < Self::ENCODED_LEN {
27630 panic!(
27631 "buffer is too small (need {} bytes, but got {})",
27632 Self::ENCODED_LEN,
27633 __tmp.remaining(),
27634 )
27635 }
27636 __tmp.put_u8(self.target_system);
27637 __tmp.put_u8(self.target_component);
27638 if matches!(version, MavlinkVersion::V2) {
27639 let len = __tmp.len();
27640 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27641 } else {
27642 __tmp.len()
27643 }
27644 }
27645}
27646#[doc = "id: 87"]
27647#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way."]
27648#[derive(Debug, Clone, PartialEq)]
27649#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27650#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27651pub struct POSITION_TARGET_GLOBAL_INT_DATA {
27652 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
27653 pub time_boot_ms: u32,
27654 #[doc = "Latitude in WGS84 frame"]
27655 pub lat_int: i32,
27656 #[doc = "Longitude in WGS84 frame"]
27657 pub lon_int: i32,
27658 #[doc = "Altitude (MSL, AGL or relative to home altitude, depending on frame)"]
27659 pub alt: f32,
27660 #[doc = "X velocity in NED frame"]
27661 pub vx: f32,
27662 #[doc = "Y velocity in NED frame"]
27663 pub vy: f32,
27664 #[doc = "Z velocity in NED frame"]
27665 pub vz: f32,
27666 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27667 pub afx: f32,
27668 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27669 pub afy: f32,
27670 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
27671 pub afz: f32,
27672 #[doc = "yaw setpoint"]
27673 pub yaw: f32,
27674 #[doc = "yaw rate setpoint"]
27675 pub yaw_rate: f32,
27676 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
27677 pub type_mask: PositionTargetTypemask,
27678 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
27679 pub coordinate_frame: MavFrame,
27680}
27681impl POSITION_TARGET_GLOBAL_INT_DATA {
27682 pub const ENCODED_LEN: usize = 51usize;
27683 pub const DEFAULT: Self = Self {
27684 time_boot_ms: 0_u32,
27685 lat_int: 0_i32,
27686 lon_int: 0_i32,
27687 alt: 0.0_f32,
27688 vx: 0.0_f32,
27689 vy: 0.0_f32,
27690 vz: 0.0_f32,
27691 afx: 0.0_f32,
27692 afy: 0.0_f32,
27693 afz: 0.0_f32,
27694 yaw: 0.0_f32,
27695 yaw_rate: 0.0_f32,
27696 type_mask: PositionTargetTypemask::DEFAULT,
27697 coordinate_frame: MavFrame::DEFAULT,
27698 };
27699 #[cfg(feature = "arbitrary")]
27700 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27701 use arbitrary::{Arbitrary, Unstructured};
27702 let mut buf = [0u8; 1024];
27703 rng.fill_bytes(&mut buf);
27704 let mut unstructured = Unstructured::new(&buf);
27705 Self::arbitrary(&mut unstructured).unwrap_or_default()
27706 }
27707}
27708impl Default for POSITION_TARGET_GLOBAL_INT_DATA {
27709 fn default() -> Self {
27710 Self::DEFAULT.clone()
27711 }
27712}
27713impl MessageData for POSITION_TARGET_GLOBAL_INT_DATA {
27714 type Message = MavMessage;
27715 const ID: u32 = 87u32;
27716 const NAME: &'static str = "POSITION_TARGET_GLOBAL_INT";
27717 const EXTRA_CRC: u8 = 150u8;
27718 const ENCODED_LEN: usize = 51usize;
27719 fn deser(
27720 _version: MavlinkVersion,
27721 __input: &[u8],
27722 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27723 let avail_len = __input.len();
27724 let mut payload_buf = [0; Self::ENCODED_LEN];
27725 let mut buf = if avail_len < Self::ENCODED_LEN {
27726 payload_buf[0..avail_len].copy_from_slice(__input);
27727 Bytes::new(&payload_buf)
27728 } else {
27729 Bytes::new(__input)
27730 };
27731 let mut __struct = Self::default();
27732 __struct.time_boot_ms = buf.get_u32_le();
27733 __struct.lat_int = buf.get_i32_le();
27734 __struct.lon_int = buf.get_i32_le();
27735 __struct.alt = buf.get_f32_le();
27736 __struct.vx = buf.get_f32_le();
27737 __struct.vy = buf.get_f32_le();
27738 __struct.vz = buf.get_f32_le();
27739 __struct.afx = buf.get_f32_le();
27740 __struct.afy = buf.get_f32_le();
27741 __struct.afz = buf.get_f32_le();
27742 __struct.yaw = buf.get_f32_le();
27743 __struct.yaw_rate = buf.get_f32_le();
27744 let tmp = buf.get_u16_le();
27745 __struct.type_mask = PositionTargetTypemask::from_bits(
27746 tmp & PositionTargetTypemask::all().bits(),
27747 )
27748 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
27749 flag_type: "PositionTargetTypemask",
27750 value: tmp as u32,
27751 })?;
27752 let tmp = buf.get_u8();
27753 __struct.coordinate_frame =
27754 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27755 enum_type: "MavFrame",
27756 value: tmp as u32,
27757 })?;
27758 Ok(__struct)
27759 }
27760 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27761 let mut __tmp = BytesMut::new(bytes);
27762 #[allow(clippy::absurd_extreme_comparisons)]
27763 #[allow(unused_comparisons)]
27764 if __tmp.remaining() < Self::ENCODED_LEN {
27765 panic!(
27766 "buffer is too small (need {} bytes, but got {})",
27767 Self::ENCODED_LEN,
27768 __tmp.remaining(),
27769 )
27770 }
27771 __tmp.put_u32_le(self.time_boot_ms);
27772 __tmp.put_i32_le(self.lat_int);
27773 __tmp.put_i32_le(self.lon_int);
27774 __tmp.put_f32_le(self.alt);
27775 __tmp.put_f32_le(self.vx);
27776 __tmp.put_f32_le(self.vy);
27777 __tmp.put_f32_le(self.vz);
27778 __tmp.put_f32_le(self.afx);
27779 __tmp.put_f32_le(self.afy);
27780 __tmp.put_f32_le(self.afz);
27781 __tmp.put_f32_le(self.yaw);
27782 __tmp.put_f32_le(self.yaw_rate);
27783 __tmp.put_u16_le(self.type_mask.bits());
27784 __tmp.put_u8(self.coordinate_frame as u8);
27785 if matches!(version, MavlinkVersion::V2) {
27786 let len = __tmp.len();
27787 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27788 } else {
27789 __tmp.len()
27790 }
27791 }
27792}
27793#[doc = "id: 257"]
27794#[doc = "Report button state change."]
27795#[derive(Debug, Clone, PartialEq)]
27796#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27797#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27798pub struct BUTTON_CHANGE_DATA {
27799 #[doc = "Timestamp (time since system boot)."]
27800 pub time_boot_ms: u32,
27801 #[doc = "Time of last change of button state."]
27802 pub last_change_ms: u32,
27803 #[doc = "Bitmap for state of buttons."]
27804 pub state: u8,
27805}
27806impl BUTTON_CHANGE_DATA {
27807 pub const ENCODED_LEN: usize = 9usize;
27808 pub const DEFAULT: Self = Self {
27809 time_boot_ms: 0_u32,
27810 last_change_ms: 0_u32,
27811 state: 0_u8,
27812 };
27813 #[cfg(feature = "arbitrary")]
27814 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27815 use arbitrary::{Arbitrary, Unstructured};
27816 let mut buf = [0u8; 1024];
27817 rng.fill_bytes(&mut buf);
27818 let mut unstructured = Unstructured::new(&buf);
27819 Self::arbitrary(&mut unstructured).unwrap_or_default()
27820 }
27821}
27822impl Default for BUTTON_CHANGE_DATA {
27823 fn default() -> Self {
27824 Self::DEFAULT.clone()
27825 }
27826}
27827impl MessageData for BUTTON_CHANGE_DATA {
27828 type Message = MavMessage;
27829 const ID: u32 = 257u32;
27830 const NAME: &'static str = "BUTTON_CHANGE";
27831 const EXTRA_CRC: u8 = 131u8;
27832 const ENCODED_LEN: usize = 9usize;
27833 fn deser(
27834 _version: MavlinkVersion,
27835 __input: &[u8],
27836 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27837 let avail_len = __input.len();
27838 let mut payload_buf = [0; Self::ENCODED_LEN];
27839 let mut buf = if avail_len < Self::ENCODED_LEN {
27840 payload_buf[0..avail_len].copy_from_slice(__input);
27841 Bytes::new(&payload_buf)
27842 } else {
27843 Bytes::new(__input)
27844 };
27845 let mut __struct = Self::default();
27846 __struct.time_boot_ms = buf.get_u32_le();
27847 __struct.last_change_ms = buf.get_u32_le();
27848 __struct.state = buf.get_u8();
27849 Ok(__struct)
27850 }
27851 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27852 let mut __tmp = BytesMut::new(bytes);
27853 #[allow(clippy::absurd_extreme_comparisons)]
27854 #[allow(unused_comparisons)]
27855 if __tmp.remaining() < Self::ENCODED_LEN {
27856 panic!(
27857 "buffer is too small (need {} bytes, but got {})",
27858 Self::ENCODED_LEN,
27859 __tmp.remaining(),
27860 )
27861 }
27862 __tmp.put_u32_le(self.time_boot_ms);
27863 __tmp.put_u32_le(self.last_change_ms);
27864 __tmp.put_u8(self.state);
27865 if matches!(version, MavlinkVersion::V2) {
27866 let len = __tmp.len();
27867 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27868 } else {
27869 __tmp.len()
27870 }
27871 }
27872}
27873#[doc = "id: 267"]
27874#[doc = "A message containing logged data which requires a LOGGING_ACK to be sent back."]
27875#[derive(Debug, Clone, PartialEq)]
27876#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27877#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27878pub struct LOGGING_DATA_ACKED_DATA {
27879 #[doc = "sequence number (can wrap)"]
27880 pub sequence: u16,
27881 #[doc = "system ID of the target"]
27882 pub target_system: u8,
27883 #[doc = "component ID of the target"]
27884 pub target_component: u8,
27885 #[doc = "data length"]
27886 pub length: u8,
27887 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
27888 pub first_message_offset: u8,
27889 #[doc = "logged data"]
27890 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27891 pub data: [u8; 249],
27892}
27893impl LOGGING_DATA_ACKED_DATA {
27894 pub const ENCODED_LEN: usize = 255usize;
27895 pub const DEFAULT: Self = Self {
27896 sequence: 0_u16,
27897 target_system: 0_u8,
27898 target_component: 0_u8,
27899 length: 0_u8,
27900 first_message_offset: 0_u8,
27901 data: [0_u8; 249usize],
27902 };
27903 #[cfg(feature = "arbitrary")]
27904 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27905 use arbitrary::{Arbitrary, Unstructured};
27906 let mut buf = [0u8; 1024];
27907 rng.fill_bytes(&mut buf);
27908 let mut unstructured = Unstructured::new(&buf);
27909 Self::arbitrary(&mut unstructured).unwrap_or_default()
27910 }
27911}
27912impl Default for LOGGING_DATA_ACKED_DATA {
27913 fn default() -> Self {
27914 Self::DEFAULT.clone()
27915 }
27916}
27917impl MessageData for LOGGING_DATA_ACKED_DATA {
27918 type Message = MavMessage;
27919 const ID: u32 = 267u32;
27920 const NAME: &'static str = "LOGGING_DATA_ACKED";
27921 const EXTRA_CRC: u8 = 35u8;
27922 const ENCODED_LEN: usize = 255usize;
27923 fn deser(
27924 _version: MavlinkVersion,
27925 __input: &[u8],
27926 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27927 let avail_len = __input.len();
27928 let mut payload_buf = [0; Self::ENCODED_LEN];
27929 let mut buf = if avail_len < Self::ENCODED_LEN {
27930 payload_buf[0..avail_len].copy_from_slice(__input);
27931 Bytes::new(&payload_buf)
27932 } else {
27933 Bytes::new(__input)
27934 };
27935 let mut __struct = Self::default();
27936 __struct.sequence = buf.get_u16_le();
27937 __struct.target_system = buf.get_u8();
27938 __struct.target_component = buf.get_u8();
27939 __struct.length = buf.get_u8();
27940 __struct.first_message_offset = buf.get_u8();
27941 for v in &mut __struct.data {
27942 let val = buf.get_u8();
27943 *v = val;
27944 }
27945 Ok(__struct)
27946 }
27947 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27948 let mut __tmp = BytesMut::new(bytes);
27949 #[allow(clippy::absurd_extreme_comparisons)]
27950 #[allow(unused_comparisons)]
27951 if __tmp.remaining() < Self::ENCODED_LEN {
27952 panic!(
27953 "buffer is too small (need {} bytes, but got {})",
27954 Self::ENCODED_LEN,
27955 __tmp.remaining(),
27956 )
27957 }
27958 __tmp.put_u16_le(self.sequence);
27959 __tmp.put_u8(self.target_system);
27960 __tmp.put_u8(self.target_component);
27961 __tmp.put_u8(self.length);
27962 __tmp.put_u8(self.first_message_offset);
27963 for val in &self.data {
27964 __tmp.put_u8(*val);
27965 }
27966 if matches!(version, MavlinkVersion::V2) {
27967 let len = __tmp.len();
27968 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27969 } else {
27970 __tmp.len()
27971 }
27972 }
27973}
27974#[doc = "id: 118"]
27975#[doc = "Reply to LOG_REQUEST_LIST."]
27976#[derive(Debug, Clone, PartialEq)]
27977#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27978#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27979pub struct LOG_ENTRY_DATA {
27980 #[doc = "UTC timestamp of log since 1970, or 0 if not available"]
27981 pub time_utc: u32,
27982 #[doc = "Size of the log (may be approximate)"]
27983 pub size: u32,
27984 #[doc = "Log id"]
27985 pub id: u16,
27986 #[doc = "Total number of logs"]
27987 pub num_logs: u16,
27988 #[doc = "High log number"]
27989 pub last_log_num: u16,
27990}
27991impl LOG_ENTRY_DATA {
27992 pub const ENCODED_LEN: usize = 14usize;
27993 pub const DEFAULT: Self = Self {
27994 time_utc: 0_u32,
27995 size: 0_u32,
27996 id: 0_u16,
27997 num_logs: 0_u16,
27998 last_log_num: 0_u16,
27999 };
28000 #[cfg(feature = "arbitrary")]
28001 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28002 use arbitrary::{Arbitrary, Unstructured};
28003 let mut buf = [0u8; 1024];
28004 rng.fill_bytes(&mut buf);
28005 let mut unstructured = Unstructured::new(&buf);
28006 Self::arbitrary(&mut unstructured).unwrap_or_default()
28007 }
28008}
28009impl Default for LOG_ENTRY_DATA {
28010 fn default() -> Self {
28011 Self::DEFAULT.clone()
28012 }
28013}
28014impl MessageData for LOG_ENTRY_DATA {
28015 type Message = MavMessage;
28016 const ID: u32 = 118u32;
28017 const NAME: &'static str = "LOG_ENTRY";
28018 const EXTRA_CRC: u8 = 56u8;
28019 const ENCODED_LEN: usize = 14usize;
28020 fn deser(
28021 _version: MavlinkVersion,
28022 __input: &[u8],
28023 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28024 let avail_len = __input.len();
28025 let mut payload_buf = [0; Self::ENCODED_LEN];
28026 let mut buf = if avail_len < Self::ENCODED_LEN {
28027 payload_buf[0..avail_len].copy_from_slice(__input);
28028 Bytes::new(&payload_buf)
28029 } else {
28030 Bytes::new(__input)
28031 };
28032 let mut __struct = Self::default();
28033 __struct.time_utc = buf.get_u32_le();
28034 __struct.size = buf.get_u32_le();
28035 __struct.id = buf.get_u16_le();
28036 __struct.num_logs = buf.get_u16_le();
28037 __struct.last_log_num = buf.get_u16_le();
28038 Ok(__struct)
28039 }
28040 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28041 let mut __tmp = BytesMut::new(bytes);
28042 #[allow(clippy::absurd_extreme_comparisons)]
28043 #[allow(unused_comparisons)]
28044 if __tmp.remaining() < Self::ENCODED_LEN {
28045 panic!(
28046 "buffer is too small (need {} bytes, but got {})",
28047 Self::ENCODED_LEN,
28048 __tmp.remaining(),
28049 )
28050 }
28051 __tmp.put_u32_le(self.time_utc);
28052 __tmp.put_u32_le(self.size);
28053 __tmp.put_u16_le(self.id);
28054 __tmp.put_u16_le(self.num_logs);
28055 __tmp.put_u16_le(self.last_log_num);
28056 if matches!(version, MavlinkVersion::V2) {
28057 let len = __tmp.len();
28058 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28059 } else {
28060 __tmp.len()
28061 }
28062 }
28063}
28064#[doc = "id: 284"]
28065#[doc = "Low level message to control a gimbal device's attitude. \t This message is to be sent from the gimbal manager to the gimbal device component. \t The quaternion and angular velocities can be set to NaN according to use case. \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. \t These rules are to ensure backwards compatibility. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."]
28066#[derive(Debug, Clone, PartialEq)]
28067#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28068#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28069pub struct GIMBAL_DEVICE_SET_ATTITUDE_DATA {
28070 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored."]
28071 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28072 pub q: [f32; 4],
28073 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored."]
28074 pub angular_velocity_x: f32,
28075 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored."]
28076 pub angular_velocity_y: f32,
28077 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored."]
28078 pub angular_velocity_z: f32,
28079 #[doc = "Low level gimbal flags."]
28080 pub flags: GimbalDeviceFlags,
28081 #[doc = "System ID"]
28082 pub target_system: u8,
28083 #[doc = "Component ID"]
28084 pub target_component: u8,
28085}
28086impl GIMBAL_DEVICE_SET_ATTITUDE_DATA {
28087 pub const ENCODED_LEN: usize = 32usize;
28088 pub const DEFAULT: Self = Self {
28089 q: [0.0_f32; 4usize],
28090 angular_velocity_x: 0.0_f32,
28091 angular_velocity_y: 0.0_f32,
28092 angular_velocity_z: 0.0_f32,
28093 flags: GimbalDeviceFlags::DEFAULT,
28094 target_system: 0_u8,
28095 target_component: 0_u8,
28096 };
28097 #[cfg(feature = "arbitrary")]
28098 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28099 use arbitrary::{Arbitrary, Unstructured};
28100 let mut buf = [0u8; 1024];
28101 rng.fill_bytes(&mut buf);
28102 let mut unstructured = Unstructured::new(&buf);
28103 Self::arbitrary(&mut unstructured).unwrap_or_default()
28104 }
28105}
28106impl Default for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
28107 fn default() -> Self {
28108 Self::DEFAULT.clone()
28109 }
28110}
28111impl MessageData for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
28112 type Message = MavMessage;
28113 const ID: u32 = 284u32;
28114 const NAME: &'static str = "GIMBAL_DEVICE_SET_ATTITUDE";
28115 const EXTRA_CRC: u8 = 99u8;
28116 const ENCODED_LEN: usize = 32usize;
28117 fn deser(
28118 _version: MavlinkVersion,
28119 __input: &[u8],
28120 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28121 let avail_len = __input.len();
28122 let mut payload_buf = [0; Self::ENCODED_LEN];
28123 let mut buf = if avail_len < Self::ENCODED_LEN {
28124 payload_buf[0..avail_len].copy_from_slice(__input);
28125 Bytes::new(&payload_buf)
28126 } else {
28127 Bytes::new(__input)
28128 };
28129 let mut __struct = Self::default();
28130 for v in &mut __struct.q {
28131 let val = buf.get_f32_le();
28132 *v = val;
28133 }
28134 __struct.angular_velocity_x = buf.get_f32_le();
28135 __struct.angular_velocity_y = buf.get_f32_le();
28136 __struct.angular_velocity_z = buf.get_f32_le();
28137 let tmp = buf.get_u16_le();
28138 __struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits())
28139 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28140 flag_type: "GimbalDeviceFlags",
28141 value: tmp as u32,
28142 })?;
28143 __struct.target_system = buf.get_u8();
28144 __struct.target_component = buf.get_u8();
28145 Ok(__struct)
28146 }
28147 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28148 let mut __tmp = BytesMut::new(bytes);
28149 #[allow(clippy::absurd_extreme_comparisons)]
28150 #[allow(unused_comparisons)]
28151 if __tmp.remaining() < Self::ENCODED_LEN {
28152 panic!(
28153 "buffer is too small (need {} bytes, but got {})",
28154 Self::ENCODED_LEN,
28155 __tmp.remaining(),
28156 )
28157 }
28158 for val in &self.q {
28159 __tmp.put_f32_le(*val);
28160 }
28161 __tmp.put_f32_le(self.angular_velocity_x);
28162 __tmp.put_f32_le(self.angular_velocity_y);
28163 __tmp.put_f32_le(self.angular_velocity_z);
28164 __tmp.put_u16_le(self.flags.bits());
28165 __tmp.put_u8(self.target_system);
28166 __tmp.put_u8(self.target_component);
28167 if matches!(version, MavlinkVersion::V2) {
28168 let len = __tmp.len();
28169 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28170 } else {
28171 __tmp.len()
28172 }
28173 }
28174}
28175#[doc = "id: 301"]
28176#[doc = "The location and information of an AIS vessel."]
28177#[derive(Debug, Clone, PartialEq)]
28178#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28179#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28180pub struct AIS_VESSEL_DATA {
28181 #[doc = "Mobile Marine Service Identifier, 9 decimal digits"]
28182 pub MMSI: u32,
28183 #[doc = "Latitude"]
28184 pub lat: i32,
28185 #[doc = "Longitude"]
28186 pub lon: i32,
28187 #[doc = "Course over ground"]
28188 pub COG: u16,
28189 #[doc = "True heading"]
28190 pub heading: u16,
28191 #[doc = "Speed over ground"]
28192 pub velocity: u16,
28193 #[doc = "Distance from lat/lon location to bow"]
28194 pub dimension_bow: u16,
28195 #[doc = "Distance from lat/lon location to stern"]
28196 pub dimension_stern: u16,
28197 #[doc = "Time since last communication in seconds"]
28198 pub tslc: u16,
28199 #[doc = "Bitmask to indicate various statuses including valid data fields"]
28200 pub flags: AisFlags,
28201 #[doc = "Turn rate"]
28202 pub turn_rate: i8,
28203 #[doc = "Navigational status"]
28204 pub navigational_status: AisNavStatus,
28205 #[doc = "Type of vessels"]
28206 pub mavtype: AisType,
28207 #[doc = "Distance from lat/lon location to port side"]
28208 pub dimension_port: u8,
28209 #[doc = "Distance from lat/lon location to starboard side"]
28210 pub dimension_starboard: u8,
28211 #[doc = "The vessel callsign"]
28212 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28213 pub callsign: [u8; 7],
28214 #[doc = "The vessel name"]
28215 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28216 pub name: [u8; 20],
28217}
28218impl AIS_VESSEL_DATA {
28219 pub const ENCODED_LEN: usize = 58usize;
28220 pub const DEFAULT: Self = Self {
28221 MMSI: 0_u32,
28222 lat: 0_i32,
28223 lon: 0_i32,
28224 COG: 0_u16,
28225 heading: 0_u16,
28226 velocity: 0_u16,
28227 dimension_bow: 0_u16,
28228 dimension_stern: 0_u16,
28229 tslc: 0_u16,
28230 flags: AisFlags::DEFAULT,
28231 turn_rate: 0_i8,
28232 navigational_status: AisNavStatus::DEFAULT,
28233 mavtype: AisType::DEFAULT,
28234 dimension_port: 0_u8,
28235 dimension_starboard: 0_u8,
28236 callsign: [0_u8; 7usize],
28237 name: [0_u8; 20usize],
28238 };
28239 #[cfg(feature = "arbitrary")]
28240 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28241 use arbitrary::{Arbitrary, Unstructured};
28242 let mut buf = [0u8; 1024];
28243 rng.fill_bytes(&mut buf);
28244 let mut unstructured = Unstructured::new(&buf);
28245 Self::arbitrary(&mut unstructured).unwrap_or_default()
28246 }
28247}
28248impl Default for AIS_VESSEL_DATA {
28249 fn default() -> Self {
28250 Self::DEFAULT.clone()
28251 }
28252}
28253impl MessageData for AIS_VESSEL_DATA {
28254 type Message = MavMessage;
28255 const ID: u32 = 301u32;
28256 const NAME: &'static str = "AIS_VESSEL";
28257 const EXTRA_CRC: u8 = 243u8;
28258 const ENCODED_LEN: usize = 58usize;
28259 fn deser(
28260 _version: MavlinkVersion,
28261 __input: &[u8],
28262 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28263 let avail_len = __input.len();
28264 let mut payload_buf = [0; Self::ENCODED_LEN];
28265 let mut buf = if avail_len < Self::ENCODED_LEN {
28266 payload_buf[0..avail_len].copy_from_slice(__input);
28267 Bytes::new(&payload_buf)
28268 } else {
28269 Bytes::new(__input)
28270 };
28271 let mut __struct = Self::default();
28272 __struct.MMSI = buf.get_u32_le();
28273 __struct.lat = buf.get_i32_le();
28274 __struct.lon = buf.get_i32_le();
28275 __struct.COG = buf.get_u16_le();
28276 __struct.heading = buf.get_u16_le();
28277 __struct.velocity = buf.get_u16_le();
28278 __struct.dimension_bow = buf.get_u16_le();
28279 __struct.dimension_stern = buf.get_u16_le();
28280 __struct.tslc = buf.get_u16_le();
28281 let tmp = buf.get_u16_le();
28282 __struct.flags = AisFlags::from_bits(tmp & AisFlags::all().bits()).ok_or(
28283 ::mavlink_core::error::ParserError::InvalidFlag {
28284 flag_type: "AisFlags",
28285 value: tmp as u32,
28286 },
28287 )?;
28288 __struct.turn_rate = buf.get_i8();
28289 let tmp = buf.get_u8();
28290 __struct.navigational_status =
28291 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28292 enum_type: "AisNavStatus",
28293 value: tmp as u32,
28294 })?;
28295 let tmp = buf.get_u8();
28296 __struct.mavtype =
28297 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28298 enum_type: "AisType",
28299 value: tmp as u32,
28300 })?;
28301 __struct.dimension_port = buf.get_u8();
28302 __struct.dimension_starboard = buf.get_u8();
28303 for v in &mut __struct.callsign {
28304 let val = buf.get_u8();
28305 *v = val;
28306 }
28307 for v in &mut __struct.name {
28308 let val = buf.get_u8();
28309 *v = val;
28310 }
28311 Ok(__struct)
28312 }
28313 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28314 let mut __tmp = BytesMut::new(bytes);
28315 #[allow(clippy::absurd_extreme_comparisons)]
28316 #[allow(unused_comparisons)]
28317 if __tmp.remaining() < Self::ENCODED_LEN {
28318 panic!(
28319 "buffer is too small (need {} bytes, but got {})",
28320 Self::ENCODED_LEN,
28321 __tmp.remaining(),
28322 )
28323 }
28324 __tmp.put_u32_le(self.MMSI);
28325 __tmp.put_i32_le(self.lat);
28326 __tmp.put_i32_le(self.lon);
28327 __tmp.put_u16_le(self.COG);
28328 __tmp.put_u16_le(self.heading);
28329 __tmp.put_u16_le(self.velocity);
28330 __tmp.put_u16_le(self.dimension_bow);
28331 __tmp.put_u16_le(self.dimension_stern);
28332 __tmp.put_u16_le(self.tslc);
28333 __tmp.put_u16_le(self.flags.bits());
28334 __tmp.put_i8(self.turn_rate);
28335 __tmp.put_u8(self.navigational_status as u8);
28336 __tmp.put_u8(self.mavtype as u8);
28337 __tmp.put_u8(self.dimension_port);
28338 __tmp.put_u8(self.dimension_starboard);
28339 for val in &self.callsign {
28340 __tmp.put_u8(*val);
28341 }
28342 for val in &self.name {
28343 __tmp.put_u8(*val);
28344 }
28345 if matches!(version, MavlinkVersion::V2) {
28346 let len = __tmp.len();
28347 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28348 } else {
28349 __tmp.len()
28350 }
28351 }
28352}
28353#[doc = "id: 333"]
28354#[doc = "Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED)."]
28355#[derive(Debug, Clone, PartialEq)]
28356#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28357#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28358pub struct TRAJECTORY_REPRESENTATION_BEZIER_DATA {
28359 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
28360 pub time_usec: u64,
28361 #[doc = "X-coordinate of bezier control points. Set to NaN if not being used"]
28362 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28363 pub pos_x: [f32; 5],
28364 #[doc = "Y-coordinate of bezier control points. Set to NaN if not being used"]
28365 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28366 pub pos_y: [f32; 5],
28367 #[doc = "Z-coordinate of bezier control points. Set to NaN if not being used"]
28368 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28369 pub pos_z: [f32; 5],
28370 #[doc = "Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated"]
28371 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28372 pub delta: [f32; 5],
28373 #[doc = "Yaw. Set to NaN for unchanged"]
28374 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28375 pub pos_yaw: [f32; 5],
28376 #[doc = "Number of valid control points (up-to 5 points are possible)"]
28377 pub valid_points: u8,
28378}
28379impl TRAJECTORY_REPRESENTATION_BEZIER_DATA {
28380 pub const ENCODED_LEN: usize = 109usize;
28381 pub const DEFAULT: Self = Self {
28382 time_usec: 0_u64,
28383 pos_x: [0.0_f32; 5usize],
28384 pos_y: [0.0_f32; 5usize],
28385 pos_z: [0.0_f32; 5usize],
28386 delta: [0.0_f32; 5usize],
28387 pos_yaw: [0.0_f32; 5usize],
28388 valid_points: 0_u8,
28389 };
28390 #[cfg(feature = "arbitrary")]
28391 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28392 use arbitrary::{Arbitrary, Unstructured};
28393 let mut buf = [0u8; 1024];
28394 rng.fill_bytes(&mut buf);
28395 let mut unstructured = Unstructured::new(&buf);
28396 Self::arbitrary(&mut unstructured).unwrap_or_default()
28397 }
28398}
28399impl Default for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
28400 fn default() -> Self {
28401 Self::DEFAULT.clone()
28402 }
28403}
28404impl MessageData for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
28405 type Message = MavMessage;
28406 const ID: u32 = 333u32;
28407 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_BEZIER";
28408 const EXTRA_CRC: u8 = 231u8;
28409 const ENCODED_LEN: usize = 109usize;
28410 fn deser(
28411 _version: MavlinkVersion,
28412 __input: &[u8],
28413 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28414 let avail_len = __input.len();
28415 let mut payload_buf = [0; Self::ENCODED_LEN];
28416 let mut buf = if avail_len < Self::ENCODED_LEN {
28417 payload_buf[0..avail_len].copy_from_slice(__input);
28418 Bytes::new(&payload_buf)
28419 } else {
28420 Bytes::new(__input)
28421 };
28422 let mut __struct = Self::default();
28423 __struct.time_usec = buf.get_u64_le();
28424 for v in &mut __struct.pos_x {
28425 let val = buf.get_f32_le();
28426 *v = val;
28427 }
28428 for v in &mut __struct.pos_y {
28429 let val = buf.get_f32_le();
28430 *v = val;
28431 }
28432 for v in &mut __struct.pos_z {
28433 let val = buf.get_f32_le();
28434 *v = val;
28435 }
28436 for v in &mut __struct.delta {
28437 let val = buf.get_f32_le();
28438 *v = val;
28439 }
28440 for v in &mut __struct.pos_yaw {
28441 let val = buf.get_f32_le();
28442 *v = val;
28443 }
28444 __struct.valid_points = buf.get_u8();
28445 Ok(__struct)
28446 }
28447 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28448 let mut __tmp = BytesMut::new(bytes);
28449 #[allow(clippy::absurd_extreme_comparisons)]
28450 #[allow(unused_comparisons)]
28451 if __tmp.remaining() < Self::ENCODED_LEN {
28452 panic!(
28453 "buffer is too small (need {} bytes, but got {})",
28454 Self::ENCODED_LEN,
28455 __tmp.remaining(),
28456 )
28457 }
28458 __tmp.put_u64_le(self.time_usec);
28459 for val in &self.pos_x {
28460 __tmp.put_f32_le(*val);
28461 }
28462 for val in &self.pos_y {
28463 __tmp.put_f32_le(*val);
28464 }
28465 for val in &self.pos_z {
28466 __tmp.put_f32_le(*val);
28467 }
28468 for val in &self.delta {
28469 __tmp.put_f32_le(*val);
28470 }
28471 for val in &self.pos_yaw {
28472 __tmp.put_f32_le(*val);
28473 }
28474 __tmp.put_u8(self.valid_points);
28475 if matches!(version, MavlinkVersion::V2) {
28476 let len = __tmp.len();
28477 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28478 } else {
28479 __tmp.len()
28480 }
28481 }
28482}
28483#[doc = "id: 192"]
28484#[doc = "Reports results of completed compass calibration. Sent until MAG_CAL_ACK received."]
28485#[derive(Debug, Clone, PartialEq)]
28486#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28487#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28488pub struct MAG_CAL_REPORT_DATA {
28489 #[doc = "RMS milligauss residuals."]
28490 pub fitness: f32,
28491 #[doc = "X offset."]
28492 pub ofs_x: f32,
28493 #[doc = "Y offset."]
28494 pub ofs_y: f32,
28495 #[doc = "Z offset."]
28496 pub ofs_z: f32,
28497 #[doc = "X diagonal (matrix 11)."]
28498 pub diag_x: f32,
28499 #[doc = "Y diagonal (matrix 22)."]
28500 pub diag_y: f32,
28501 #[doc = "Z diagonal (matrix 33)."]
28502 pub diag_z: f32,
28503 #[doc = "X off-diagonal (matrix 12 and 21)."]
28504 pub offdiag_x: f32,
28505 #[doc = "Y off-diagonal (matrix 13 and 31)."]
28506 pub offdiag_y: f32,
28507 #[doc = "Z off-diagonal (matrix 32 and 23)."]
28508 pub offdiag_z: f32,
28509 #[doc = "Compass being calibrated."]
28510 pub compass_id: u8,
28511 #[doc = "Bitmask of compasses being calibrated."]
28512 pub cal_mask: u8,
28513 #[doc = "Calibration Status."]
28514 pub cal_status: MagCalStatus,
28515 #[doc = "0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters."]
28516 pub autosaved: u8,
28517 #[doc = "Confidence in orientation (higher is better)."]
28518 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28519 pub orientation_confidence: f32,
28520 #[doc = "orientation before calibration."]
28521 #[cfg_attr(feature = "serde", serde(default))]
28522 pub old_orientation: MavSensorOrientation,
28523 #[doc = "orientation after calibration."]
28524 #[cfg_attr(feature = "serde", serde(default))]
28525 pub new_orientation: MavSensorOrientation,
28526 #[doc = "field radius correction factor"]
28527 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28528 pub scale_factor: f32,
28529}
28530impl MAG_CAL_REPORT_DATA {
28531 pub const ENCODED_LEN: usize = 54usize;
28532 pub const DEFAULT: Self = Self {
28533 fitness: 0.0_f32,
28534 ofs_x: 0.0_f32,
28535 ofs_y: 0.0_f32,
28536 ofs_z: 0.0_f32,
28537 diag_x: 0.0_f32,
28538 diag_y: 0.0_f32,
28539 diag_z: 0.0_f32,
28540 offdiag_x: 0.0_f32,
28541 offdiag_y: 0.0_f32,
28542 offdiag_z: 0.0_f32,
28543 compass_id: 0_u8,
28544 cal_mask: 0_u8,
28545 cal_status: MagCalStatus::DEFAULT,
28546 autosaved: 0_u8,
28547 orientation_confidence: 0.0_f32,
28548 old_orientation: MavSensorOrientation::DEFAULT,
28549 new_orientation: MavSensorOrientation::DEFAULT,
28550 scale_factor: 0.0_f32,
28551 };
28552 #[cfg(feature = "arbitrary")]
28553 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28554 use arbitrary::{Arbitrary, Unstructured};
28555 let mut buf = [0u8; 1024];
28556 rng.fill_bytes(&mut buf);
28557 let mut unstructured = Unstructured::new(&buf);
28558 Self::arbitrary(&mut unstructured).unwrap_or_default()
28559 }
28560}
28561impl Default for MAG_CAL_REPORT_DATA {
28562 fn default() -> Self {
28563 Self::DEFAULT.clone()
28564 }
28565}
28566impl MessageData for MAG_CAL_REPORT_DATA {
28567 type Message = MavMessage;
28568 const ID: u32 = 192u32;
28569 const NAME: &'static str = "MAG_CAL_REPORT";
28570 const EXTRA_CRC: u8 = 36u8;
28571 const ENCODED_LEN: usize = 54usize;
28572 fn deser(
28573 _version: MavlinkVersion,
28574 __input: &[u8],
28575 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28576 let avail_len = __input.len();
28577 let mut payload_buf = [0; Self::ENCODED_LEN];
28578 let mut buf = if avail_len < Self::ENCODED_LEN {
28579 payload_buf[0..avail_len].copy_from_slice(__input);
28580 Bytes::new(&payload_buf)
28581 } else {
28582 Bytes::new(__input)
28583 };
28584 let mut __struct = Self::default();
28585 __struct.fitness = buf.get_f32_le();
28586 __struct.ofs_x = buf.get_f32_le();
28587 __struct.ofs_y = buf.get_f32_le();
28588 __struct.ofs_z = buf.get_f32_le();
28589 __struct.diag_x = buf.get_f32_le();
28590 __struct.diag_y = buf.get_f32_le();
28591 __struct.diag_z = buf.get_f32_le();
28592 __struct.offdiag_x = buf.get_f32_le();
28593 __struct.offdiag_y = buf.get_f32_le();
28594 __struct.offdiag_z = buf.get_f32_le();
28595 __struct.compass_id = buf.get_u8();
28596 __struct.cal_mask = buf.get_u8();
28597 let tmp = buf.get_u8();
28598 __struct.cal_status =
28599 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28600 enum_type: "MagCalStatus",
28601 value: tmp as u32,
28602 })?;
28603 __struct.autosaved = buf.get_u8();
28604 __struct.orientation_confidence = buf.get_f32_le();
28605 let tmp = buf.get_u8();
28606 __struct.old_orientation =
28607 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28608 enum_type: "MavSensorOrientation",
28609 value: tmp as u32,
28610 })?;
28611 let tmp = buf.get_u8();
28612 __struct.new_orientation =
28613 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28614 enum_type: "MavSensorOrientation",
28615 value: tmp as u32,
28616 })?;
28617 __struct.scale_factor = buf.get_f32_le();
28618 Ok(__struct)
28619 }
28620 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28621 let mut __tmp = BytesMut::new(bytes);
28622 #[allow(clippy::absurd_extreme_comparisons)]
28623 #[allow(unused_comparisons)]
28624 if __tmp.remaining() < Self::ENCODED_LEN {
28625 panic!(
28626 "buffer is too small (need {} bytes, but got {})",
28627 Self::ENCODED_LEN,
28628 __tmp.remaining(),
28629 )
28630 }
28631 __tmp.put_f32_le(self.fitness);
28632 __tmp.put_f32_le(self.ofs_x);
28633 __tmp.put_f32_le(self.ofs_y);
28634 __tmp.put_f32_le(self.ofs_z);
28635 __tmp.put_f32_le(self.diag_x);
28636 __tmp.put_f32_le(self.diag_y);
28637 __tmp.put_f32_le(self.diag_z);
28638 __tmp.put_f32_le(self.offdiag_x);
28639 __tmp.put_f32_le(self.offdiag_y);
28640 __tmp.put_f32_le(self.offdiag_z);
28641 __tmp.put_u8(self.compass_id);
28642 __tmp.put_u8(self.cal_mask);
28643 __tmp.put_u8(self.cal_status as u8);
28644 __tmp.put_u8(self.autosaved);
28645 __tmp.put_f32_le(self.orientation_confidence);
28646 __tmp.put_u8(self.old_orientation as u8);
28647 __tmp.put_u8(self.new_orientation as u8);
28648 __tmp.put_f32_le(self.scale_factor);
28649 if matches!(version, MavlinkVersion::V2) {
28650 let len = __tmp.len();
28651 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28652 } else {
28653 __tmp.len()
28654 }
28655 }
28656}
28657#[doc = "id: 124"]
28658#[doc = "Second GPS data."]
28659#[derive(Debug, Clone, PartialEq)]
28660#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28661#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28662pub struct GPS2_RAW_DATA {
28663 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
28664 pub time_usec: u64,
28665 #[doc = "Latitude (WGS84)"]
28666 pub lat: i32,
28667 #[doc = "Longitude (WGS84)"]
28668 pub lon: i32,
28669 #[doc = "Altitude (MSL). Positive for up."]
28670 pub alt: i32,
28671 #[doc = "Age of DGPS info"]
28672 pub dgps_age: u32,
28673 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
28674 pub eph: u16,
28675 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
28676 pub epv: u16,
28677 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
28678 pub vel: u16,
28679 #[doc = "Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
28680 pub cog: u16,
28681 #[doc = "GPS fix type."]
28682 pub fix_type: GpsFixType,
28683 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
28684 pub satellites_visible: u8,
28685 #[doc = "Number of DGPS satellites"]
28686 pub dgps_numch: u8,
28687 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
28688 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28689 pub yaw: u16,
28690 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
28691 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28692 pub alt_ellipsoid: i32,
28693 #[doc = "Position uncertainty."]
28694 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28695 pub h_acc: u32,
28696 #[doc = "Altitude uncertainty."]
28697 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28698 pub v_acc: u32,
28699 #[doc = "Speed uncertainty."]
28700 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28701 pub vel_acc: u32,
28702 #[doc = "Heading / track uncertainty"]
28703 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28704 pub hdg_acc: u32,
28705}
28706impl GPS2_RAW_DATA {
28707 pub const ENCODED_LEN: usize = 57usize;
28708 pub const DEFAULT: Self = Self {
28709 time_usec: 0_u64,
28710 lat: 0_i32,
28711 lon: 0_i32,
28712 alt: 0_i32,
28713 dgps_age: 0_u32,
28714 eph: 0_u16,
28715 epv: 0_u16,
28716 vel: 0_u16,
28717 cog: 0_u16,
28718 fix_type: GpsFixType::DEFAULT,
28719 satellites_visible: 0_u8,
28720 dgps_numch: 0_u8,
28721 yaw: 0_u16,
28722 alt_ellipsoid: 0_i32,
28723 h_acc: 0_u32,
28724 v_acc: 0_u32,
28725 vel_acc: 0_u32,
28726 hdg_acc: 0_u32,
28727 };
28728 #[cfg(feature = "arbitrary")]
28729 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28730 use arbitrary::{Arbitrary, Unstructured};
28731 let mut buf = [0u8; 1024];
28732 rng.fill_bytes(&mut buf);
28733 let mut unstructured = Unstructured::new(&buf);
28734 Self::arbitrary(&mut unstructured).unwrap_or_default()
28735 }
28736}
28737impl Default for GPS2_RAW_DATA {
28738 fn default() -> Self {
28739 Self::DEFAULT.clone()
28740 }
28741}
28742impl MessageData for GPS2_RAW_DATA {
28743 type Message = MavMessage;
28744 const ID: u32 = 124u32;
28745 const NAME: &'static str = "GPS2_RAW";
28746 const EXTRA_CRC: u8 = 87u8;
28747 const ENCODED_LEN: usize = 57usize;
28748 fn deser(
28749 _version: MavlinkVersion,
28750 __input: &[u8],
28751 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28752 let avail_len = __input.len();
28753 let mut payload_buf = [0; Self::ENCODED_LEN];
28754 let mut buf = if avail_len < Self::ENCODED_LEN {
28755 payload_buf[0..avail_len].copy_from_slice(__input);
28756 Bytes::new(&payload_buf)
28757 } else {
28758 Bytes::new(__input)
28759 };
28760 let mut __struct = Self::default();
28761 __struct.time_usec = buf.get_u64_le();
28762 __struct.lat = buf.get_i32_le();
28763 __struct.lon = buf.get_i32_le();
28764 __struct.alt = buf.get_i32_le();
28765 __struct.dgps_age = buf.get_u32_le();
28766 __struct.eph = buf.get_u16_le();
28767 __struct.epv = buf.get_u16_le();
28768 __struct.vel = buf.get_u16_le();
28769 __struct.cog = buf.get_u16_le();
28770 let tmp = buf.get_u8();
28771 __struct.fix_type =
28772 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28773 enum_type: "GpsFixType",
28774 value: tmp as u32,
28775 })?;
28776 __struct.satellites_visible = buf.get_u8();
28777 __struct.dgps_numch = buf.get_u8();
28778 __struct.yaw = buf.get_u16_le();
28779 __struct.alt_ellipsoid = buf.get_i32_le();
28780 __struct.h_acc = buf.get_u32_le();
28781 __struct.v_acc = buf.get_u32_le();
28782 __struct.vel_acc = buf.get_u32_le();
28783 __struct.hdg_acc = buf.get_u32_le();
28784 Ok(__struct)
28785 }
28786 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28787 let mut __tmp = BytesMut::new(bytes);
28788 #[allow(clippy::absurd_extreme_comparisons)]
28789 #[allow(unused_comparisons)]
28790 if __tmp.remaining() < Self::ENCODED_LEN {
28791 panic!(
28792 "buffer is too small (need {} bytes, but got {})",
28793 Self::ENCODED_LEN,
28794 __tmp.remaining(),
28795 )
28796 }
28797 __tmp.put_u64_le(self.time_usec);
28798 __tmp.put_i32_le(self.lat);
28799 __tmp.put_i32_le(self.lon);
28800 __tmp.put_i32_le(self.alt);
28801 __tmp.put_u32_le(self.dgps_age);
28802 __tmp.put_u16_le(self.eph);
28803 __tmp.put_u16_le(self.epv);
28804 __tmp.put_u16_le(self.vel);
28805 __tmp.put_u16_le(self.cog);
28806 __tmp.put_u8(self.fix_type as u8);
28807 __tmp.put_u8(self.satellites_visible);
28808 __tmp.put_u8(self.dgps_numch);
28809 __tmp.put_u16_le(self.yaw);
28810 __tmp.put_i32_le(self.alt_ellipsoid);
28811 __tmp.put_u32_le(self.h_acc);
28812 __tmp.put_u32_le(self.v_acc);
28813 __tmp.put_u32_le(self.vel_acc);
28814 __tmp.put_u32_le(self.hdg_acc);
28815 if matches!(version, MavlinkVersion::V2) {
28816 let len = __tmp.len();
28817 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28818 } else {
28819 __tmp.len()
28820 }
28821 }
28822}
28823#[doc = "id: 0"]
28824#[doc = "The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at <https://mavlink.io/en/services/heartbeat.html>."]
28825#[derive(Debug, Clone, PartialEq)]
28826#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28827#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28828pub struct HEARTBEAT_DATA {
28829 #[doc = "A bitfield for use for autopilot-specific flags"]
28830 pub custom_mode: u32,
28831 #[doc = "Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type."]
28832 pub mavtype: MavType,
28833 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
28834 pub autopilot: MavAutopilot,
28835 #[doc = "System mode bitmap."]
28836 pub base_mode: MavModeFlag,
28837 #[doc = "System status flag."]
28838 pub system_status: MavState,
28839 #[doc = "MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version"]
28840 pub mavlink_version: u8,
28841}
28842impl HEARTBEAT_DATA {
28843 pub const ENCODED_LEN: usize = 9usize;
28844 pub const DEFAULT: Self = Self {
28845 custom_mode: 0_u32,
28846 mavtype: MavType::DEFAULT,
28847 autopilot: MavAutopilot::DEFAULT,
28848 base_mode: MavModeFlag::DEFAULT,
28849 system_status: MavState::DEFAULT,
28850 mavlink_version: 0_u8,
28851 };
28852 #[cfg(feature = "arbitrary")]
28853 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28854 use arbitrary::{Arbitrary, Unstructured};
28855 let mut buf = [0u8; 1024];
28856 rng.fill_bytes(&mut buf);
28857 let mut unstructured = Unstructured::new(&buf);
28858 Self::arbitrary(&mut unstructured).unwrap_or_default()
28859 }
28860}
28861impl Default for HEARTBEAT_DATA {
28862 fn default() -> Self {
28863 Self::DEFAULT.clone()
28864 }
28865}
28866impl MessageData for HEARTBEAT_DATA {
28867 type Message = MavMessage;
28868 const ID: u32 = 0u32;
28869 const NAME: &'static str = "HEARTBEAT";
28870 const EXTRA_CRC: u8 = 50u8;
28871 const ENCODED_LEN: usize = 9usize;
28872 fn deser(
28873 _version: MavlinkVersion,
28874 __input: &[u8],
28875 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28876 let avail_len = __input.len();
28877 let mut payload_buf = [0; Self::ENCODED_LEN];
28878 let mut buf = if avail_len < Self::ENCODED_LEN {
28879 payload_buf[0..avail_len].copy_from_slice(__input);
28880 Bytes::new(&payload_buf)
28881 } else {
28882 Bytes::new(__input)
28883 };
28884 let mut __struct = Self::default();
28885 __struct.custom_mode = buf.get_u32_le();
28886 let tmp = buf.get_u8();
28887 __struct.mavtype =
28888 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28889 enum_type: "MavType",
28890 value: tmp as u32,
28891 })?;
28892 let tmp = buf.get_u8();
28893 __struct.autopilot =
28894 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28895 enum_type: "MavAutopilot",
28896 value: tmp as u32,
28897 })?;
28898 let tmp = buf.get_u8();
28899 __struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
28900 ::mavlink_core::error::ParserError::InvalidFlag {
28901 flag_type: "MavModeFlag",
28902 value: tmp as u32,
28903 },
28904 )?;
28905 let tmp = buf.get_u8();
28906 __struct.system_status =
28907 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28908 enum_type: "MavState",
28909 value: tmp as u32,
28910 })?;
28911 __struct.mavlink_version = buf.get_u8();
28912 Ok(__struct)
28913 }
28914 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28915 let mut __tmp = BytesMut::new(bytes);
28916 #[allow(clippy::absurd_extreme_comparisons)]
28917 #[allow(unused_comparisons)]
28918 if __tmp.remaining() < Self::ENCODED_LEN {
28919 panic!(
28920 "buffer is too small (need {} bytes, but got {})",
28921 Self::ENCODED_LEN,
28922 __tmp.remaining(),
28923 )
28924 }
28925 __tmp.put_u32_le(self.custom_mode);
28926 __tmp.put_u8(self.mavtype as u8);
28927 __tmp.put_u8(self.autopilot as u8);
28928 __tmp.put_u8(self.base_mode.bits());
28929 __tmp.put_u8(self.system_status as u8);
28930 __tmp.put_u8(self.mavlink_version);
28931 if matches!(version, MavlinkVersion::V2) {
28932 let len = __tmp.len();
28933 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28934 } else {
28935 __tmp.len()
28936 }
28937 }
28938}
28939#[doc = "id: 1"]
28940#[doc = "The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout."]
28941#[derive(Debug, Clone, PartialEq)]
28942#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28943#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28944pub struct SYS_STATUS_DATA {
28945 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
28946 pub onboard_control_sensors_present: MavSysStatusSensor,
28947 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
28948 pub onboard_control_sensors_enabled: MavSysStatusSensor,
28949 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
28950 pub onboard_control_sensors_health: MavSysStatusSensor,
28951 #[doc = "Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000"]
28952 pub load: u16,
28953 #[doc = "Battery voltage, UINT16_MAX: Voltage not sent by autopilot"]
28954 pub voltage_battery: u16,
28955 #[doc = "Battery current, -1: Current not sent by autopilot"]
28956 pub current_battery: i16,
28957 #[doc = "Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
28958 pub drop_rate_comm: u16,
28959 #[doc = "Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
28960 pub errors_comm: u16,
28961 #[doc = "Autopilot-specific errors"]
28962 pub errors_count1: u16,
28963 #[doc = "Autopilot-specific errors"]
28964 pub errors_count2: u16,
28965 #[doc = "Autopilot-specific errors"]
28966 pub errors_count3: u16,
28967 #[doc = "Autopilot-specific errors"]
28968 pub errors_count4: u16,
28969 #[doc = "Battery energy remaining, -1: Battery remaining energy not sent by autopilot"]
28970 pub battery_remaining: i8,
28971 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
28972 #[cfg_attr(feature = "serde", serde(default))]
28973 pub onboard_control_sensors_present_extended: MavSysStatusSensorExtended,
28974 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
28975 #[cfg_attr(feature = "serde", serde(default))]
28976 pub onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended,
28977 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
28978 #[cfg_attr(feature = "serde", serde(default))]
28979 pub onboard_control_sensors_health_extended: MavSysStatusSensorExtended,
28980}
28981impl SYS_STATUS_DATA {
28982 pub const ENCODED_LEN: usize = 43usize;
28983 pub const DEFAULT: Self = Self {
28984 onboard_control_sensors_present: MavSysStatusSensor::DEFAULT,
28985 onboard_control_sensors_enabled: MavSysStatusSensor::DEFAULT,
28986 onboard_control_sensors_health: MavSysStatusSensor::DEFAULT,
28987 load: 0_u16,
28988 voltage_battery: 0_u16,
28989 current_battery: 0_i16,
28990 drop_rate_comm: 0_u16,
28991 errors_comm: 0_u16,
28992 errors_count1: 0_u16,
28993 errors_count2: 0_u16,
28994 errors_count3: 0_u16,
28995 errors_count4: 0_u16,
28996 battery_remaining: 0_i8,
28997 onboard_control_sensors_present_extended: MavSysStatusSensorExtended::DEFAULT,
28998 onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended::DEFAULT,
28999 onboard_control_sensors_health_extended: MavSysStatusSensorExtended::DEFAULT,
29000 };
29001 #[cfg(feature = "arbitrary")]
29002 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29003 use arbitrary::{Arbitrary, Unstructured};
29004 let mut buf = [0u8; 1024];
29005 rng.fill_bytes(&mut buf);
29006 let mut unstructured = Unstructured::new(&buf);
29007 Self::arbitrary(&mut unstructured).unwrap_or_default()
29008 }
29009}
29010impl Default for SYS_STATUS_DATA {
29011 fn default() -> Self {
29012 Self::DEFAULT.clone()
29013 }
29014}
29015impl MessageData for SYS_STATUS_DATA {
29016 type Message = MavMessage;
29017 const ID: u32 = 1u32;
29018 const NAME: &'static str = "SYS_STATUS";
29019 const EXTRA_CRC: u8 = 124u8;
29020 const ENCODED_LEN: usize = 43usize;
29021 fn deser(
29022 _version: MavlinkVersion,
29023 __input: &[u8],
29024 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29025 let avail_len = __input.len();
29026 let mut payload_buf = [0; Self::ENCODED_LEN];
29027 let mut buf = if avail_len < Self::ENCODED_LEN {
29028 payload_buf[0..avail_len].copy_from_slice(__input);
29029 Bytes::new(&payload_buf)
29030 } else {
29031 Bytes::new(__input)
29032 };
29033 let mut __struct = Self::default();
29034 let tmp = buf.get_u32_le();
29035 __struct.onboard_control_sensors_present = MavSysStatusSensor::from_bits(
29036 tmp & MavSysStatusSensor::all().bits(),
29037 )
29038 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29039 flag_type: "MavSysStatusSensor",
29040 value: tmp as u32,
29041 })?;
29042 let tmp = buf.get_u32_le();
29043 __struct.onboard_control_sensors_enabled = MavSysStatusSensor::from_bits(
29044 tmp & MavSysStatusSensor::all().bits(),
29045 )
29046 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29047 flag_type: "MavSysStatusSensor",
29048 value: tmp as u32,
29049 })?;
29050 let tmp = buf.get_u32_le();
29051 __struct.onboard_control_sensors_health = MavSysStatusSensor::from_bits(
29052 tmp & MavSysStatusSensor::all().bits(),
29053 )
29054 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29055 flag_type: "MavSysStatusSensor",
29056 value: tmp as u32,
29057 })?;
29058 __struct.load = buf.get_u16_le();
29059 __struct.voltage_battery = buf.get_u16_le();
29060 __struct.current_battery = buf.get_i16_le();
29061 __struct.drop_rate_comm = buf.get_u16_le();
29062 __struct.errors_comm = buf.get_u16_le();
29063 __struct.errors_count1 = buf.get_u16_le();
29064 __struct.errors_count2 = buf.get_u16_le();
29065 __struct.errors_count3 = buf.get_u16_le();
29066 __struct.errors_count4 = buf.get_u16_le();
29067 __struct.battery_remaining = buf.get_i8();
29068 let tmp = buf.get_u32_le();
29069 __struct.onboard_control_sensors_present_extended =
29070 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
29071 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29072 flag_type: "MavSysStatusSensorExtended",
29073 value: tmp as u32,
29074 })?;
29075 let tmp = buf.get_u32_le();
29076 __struct.onboard_control_sensors_enabled_extended =
29077 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
29078 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29079 flag_type: "MavSysStatusSensorExtended",
29080 value: tmp as u32,
29081 })?;
29082 let tmp = buf.get_u32_le();
29083 __struct.onboard_control_sensors_health_extended =
29084 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
29085 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29086 flag_type: "MavSysStatusSensorExtended",
29087 value: tmp as u32,
29088 })?;
29089 Ok(__struct)
29090 }
29091 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29092 let mut __tmp = BytesMut::new(bytes);
29093 #[allow(clippy::absurd_extreme_comparisons)]
29094 #[allow(unused_comparisons)]
29095 if __tmp.remaining() < Self::ENCODED_LEN {
29096 panic!(
29097 "buffer is too small (need {} bytes, but got {})",
29098 Self::ENCODED_LEN,
29099 __tmp.remaining(),
29100 )
29101 }
29102 __tmp.put_u32_le(self.onboard_control_sensors_present.bits());
29103 __tmp.put_u32_le(self.onboard_control_sensors_enabled.bits());
29104 __tmp.put_u32_le(self.onboard_control_sensors_health.bits());
29105 __tmp.put_u16_le(self.load);
29106 __tmp.put_u16_le(self.voltage_battery);
29107 __tmp.put_i16_le(self.current_battery);
29108 __tmp.put_u16_le(self.drop_rate_comm);
29109 __tmp.put_u16_le(self.errors_comm);
29110 __tmp.put_u16_le(self.errors_count1);
29111 __tmp.put_u16_le(self.errors_count2);
29112 __tmp.put_u16_le(self.errors_count3);
29113 __tmp.put_u16_le(self.errors_count4);
29114 __tmp.put_i8(self.battery_remaining);
29115 __tmp.put_u32_le(self.onboard_control_sensors_present_extended.bits());
29116 __tmp.put_u32_le(self.onboard_control_sensors_enabled_extended.bits());
29117 __tmp.put_u32_le(self.onboard_control_sensors_health_extended.bits());
29118 if matches!(version, MavlinkVersion::V2) {
29119 let len = __tmp.len();
29120 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29121 } else {
29122 __tmp.len()
29123 }
29124 }
29125}
29126#[doc = "id: 269"]
29127#[doc = "Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc."]
29128#[derive(Debug, Clone, PartialEq)]
29129#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29130#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29131pub struct VIDEO_STREAM_INFORMATION_DATA {
29132 #[doc = "Frame rate."]
29133 pub framerate: f32,
29134 #[doc = "Bit rate."]
29135 pub bitrate: u32,
29136 #[doc = "Bitmap of stream status flags."]
29137 pub flags: VideoStreamStatusFlags,
29138 #[doc = "Horizontal resolution."]
29139 pub resolution_h: u16,
29140 #[doc = "Vertical resolution."]
29141 pub resolution_v: u16,
29142 #[doc = "Video image rotation clockwise."]
29143 pub rotation: u16,
29144 #[doc = "Horizontal Field of view."]
29145 pub hfov: u16,
29146 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
29147 pub stream_id: u8,
29148 #[doc = "Number of streams available."]
29149 pub count: u8,
29150 #[doc = "Type of stream."]
29151 pub mavtype: VideoStreamType,
29152 #[doc = "Stream name."]
29153 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29154 pub name: [u8; 32],
29155 #[doc = "Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to)."]
29156 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29157 pub uri: [u8; 160],
29158 #[doc = "Encoding of stream."]
29159 #[cfg_attr(feature = "serde", serde(default))]
29160 pub encoding: VideoStreamEncoding,
29161 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
29162 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29163 pub camera_device_id: u8,
29164}
29165impl VIDEO_STREAM_INFORMATION_DATA {
29166 pub const ENCODED_LEN: usize = 215usize;
29167 pub const DEFAULT: Self = Self {
29168 framerate: 0.0_f32,
29169 bitrate: 0_u32,
29170 flags: VideoStreamStatusFlags::DEFAULT,
29171 resolution_h: 0_u16,
29172 resolution_v: 0_u16,
29173 rotation: 0_u16,
29174 hfov: 0_u16,
29175 stream_id: 0_u8,
29176 count: 0_u8,
29177 mavtype: VideoStreamType::DEFAULT,
29178 name: [0_u8; 32usize],
29179 uri: [0_u8; 160usize],
29180 encoding: VideoStreamEncoding::DEFAULT,
29181 camera_device_id: 0_u8,
29182 };
29183 #[cfg(feature = "arbitrary")]
29184 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29185 use arbitrary::{Arbitrary, Unstructured};
29186 let mut buf = [0u8; 1024];
29187 rng.fill_bytes(&mut buf);
29188 let mut unstructured = Unstructured::new(&buf);
29189 Self::arbitrary(&mut unstructured).unwrap_or_default()
29190 }
29191}
29192impl Default for VIDEO_STREAM_INFORMATION_DATA {
29193 fn default() -> Self {
29194 Self::DEFAULT.clone()
29195 }
29196}
29197impl MessageData for VIDEO_STREAM_INFORMATION_DATA {
29198 type Message = MavMessage;
29199 const ID: u32 = 269u32;
29200 const NAME: &'static str = "VIDEO_STREAM_INFORMATION";
29201 const EXTRA_CRC: u8 = 109u8;
29202 const ENCODED_LEN: usize = 215usize;
29203 fn deser(
29204 _version: MavlinkVersion,
29205 __input: &[u8],
29206 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29207 let avail_len = __input.len();
29208 let mut payload_buf = [0; Self::ENCODED_LEN];
29209 let mut buf = if avail_len < Self::ENCODED_LEN {
29210 payload_buf[0..avail_len].copy_from_slice(__input);
29211 Bytes::new(&payload_buf)
29212 } else {
29213 Bytes::new(__input)
29214 };
29215 let mut __struct = Self::default();
29216 __struct.framerate = buf.get_f32_le();
29217 __struct.bitrate = buf.get_u32_le();
29218 let tmp = buf.get_u16_le();
29219 __struct.flags = VideoStreamStatusFlags::from_bits(
29220 tmp & VideoStreamStatusFlags::all().bits(),
29221 )
29222 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29223 flag_type: "VideoStreamStatusFlags",
29224 value: tmp as u32,
29225 })?;
29226 __struct.resolution_h = buf.get_u16_le();
29227 __struct.resolution_v = buf.get_u16_le();
29228 __struct.rotation = buf.get_u16_le();
29229 __struct.hfov = buf.get_u16_le();
29230 __struct.stream_id = buf.get_u8();
29231 __struct.count = buf.get_u8();
29232 let tmp = buf.get_u8();
29233 __struct.mavtype =
29234 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29235 enum_type: "VideoStreamType",
29236 value: tmp as u32,
29237 })?;
29238 for v in &mut __struct.name {
29239 let val = buf.get_u8();
29240 *v = val;
29241 }
29242 for v in &mut __struct.uri {
29243 let val = buf.get_u8();
29244 *v = val;
29245 }
29246 let tmp = buf.get_u8();
29247 __struct.encoding =
29248 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29249 enum_type: "VideoStreamEncoding",
29250 value: tmp as u32,
29251 })?;
29252 __struct.camera_device_id = buf.get_u8();
29253 Ok(__struct)
29254 }
29255 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29256 let mut __tmp = BytesMut::new(bytes);
29257 #[allow(clippy::absurd_extreme_comparisons)]
29258 #[allow(unused_comparisons)]
29259 if __tmp.remaining() < Self::ENCODED_LEN {
29260 panic!(
29261 "buffer is too small (need {} bytes, but got {})",
29262 Self::ENCODED_LEN,
29263 __tmp.remaining(),
29264 )
29265 }
29266 __tmp.put_f32_le(self.framerate);
29267 __tmp.put_u32_le(self.bitrate);
29268 __tmp.put_u16_le(self.flags.bits());
29269 __tmp.put_u16_le(self.resolution_h);
29270 __tmp.put_u16_le(self.resolution_v);
29271 __tmp.put_u16_le(self.rotation);
29272 __tmp.put_u16_le(self.hfov);
29273 __tmp.put_u8(self.stream_id);
29274 __tmp.put_u8(self.count);
29275 __tmp.put_u8(self.mavtype as u8);
29276 for val in &self.name {
29277 __tmp.put_u8(*val);
29278 }
29279 for val in &self.uri {
29280 __tmp.put_u8(*val);
29281 }
29282 __tmp.put_u8(self.encoding as u8);
29283 __tmp.put_u8(self.camera_device_id);
29284 if matches!(version, MavlinkVersion::V2) {
29285 let len = __tmp.len();
29286 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29287 } else {
29288 __tmp.len()
29289 }
29290 }
29291}
29292#[doc = "id: 241"]
29293#[doc = "Vibration levels and accelerometer clipping."]
29294#[derive(Debug, Clone, PartialEq)]
29295#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29296#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29297pub struct VIBRATION_DATA {
29298 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
29299 pub time_usec: u64,
29300 #[doc = "Vibration levels on X-axis"]
29301 pub vibration_x: f32,
29302 #[doc = "Vibration levels on Y-axis"]
29303 pub vibration_y: f32,
29304 #[doc = "Vibration levels on Z-axis"]
29305 pub vibration_z: f32,
29306 #[doc = "first accelerometer clipping count"]
29307 pub clipping_0: u32,
29308 #[doc = "second accelerometer clipping count"]
29309 pub clipping_1: u32,
29310 #[doc = "third accelerometer clipping count"]
29311 pub clipping_2: u32,
29312}
29313impl VIBRATION_DATA {
29314 pub const ENCODED_LEN: usize = 32usize;
29315 pub const DEFAULT: Self = Self {
29316 time_usec: 0_u64,
29317 vibration_x: 0.0_f32,
29318 vibration_y: 0.0_f32,
29319 vibration_z: 0.0_f32,
29320 clipping_0: 0_u32,
29321 clipping_1: 0_u32,
29322 clipping_2: 0_u32,
29323 };
29324 #[cfg(feature = "arbitrary")]
29325 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29326 use arbitrary::{Arbitrary, Unstructured};
29327 let mut buf = [0u8; 1024];
29328 rng.fill_bytes(&mut buf);
29329 let mut unstructured = Unstructured::new(&buf);
29330 Self::arbitrary(&mut unstructured).unwrap_or_default()
29331 }
29332}
29333impl Default for VIBRATION_DATA {
29334 fn default() -> Self {
29335 Self::DEFAULT.clone()
29336 }
29337}
29338impl MessageData for VIBRATION_DATA {
29339 type Message = MavMessage;
29340 const ID: u32 = 241u32;
29341 const NAME: &'static str = "VIBRATION";
29342 const EXTRA_CRC: u8 = 90u8;
29343 const ENCODED_LEN: usize = 32usize;
29344 fn deser(
29345 _version: MavlinkVersion,
29346 __input: &[u8],
29347 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29348 let avail_len = __input.len();
29349 let mut payload_buf = [0; Self::ENCODED_LEN];
29350 let mut buf = if avail_len < Self::ENCODED_LEN {
29351 payload_buf[0..avail_len].copy_from_slice(__input);
29352 Bytes::new(&payload_buf)
29353 } else {
29354 Bytes::new(__input)
29355 };
29356 let mut __struct = Self::default();
29357 __struct.time_usec = buf.get_u64_le();
29358 __struct.vibration_x = buf.get_f32_le();
29359 __struct.vibration_y = buf.get_f32_le();
29360 __struct.vibration_z = buf.get_f32_le();
29361 __struct.clipping_0 = buf.get_u32_le();
29362 __struct.clipping_1 = buf.get_u32_le();
29363 __struct.clipping_2 = buf.get_u32_le();
29364 Ok(__struct)
29365 }
29366 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29367 let mut __tmp = BytesMut::new(bytes);
29368 #[allow(clippy::absurd_extreme_comparisons)]
29369 #[allow(unused_comparisons)]
29370 if __tmp.remaining() < Self::ENCODED_LEN {
29371 panic!(
29372 "buffer is too small (need {} bytes, but got {})",
29373 Self::ENCODED_LEN,
29374 __tmp.remaining(),
29375 )
29376 }
29377 __tmp.put_u64_le(self.time_usec);
29378 __tmp.put_f32_le(self.vibration_x);
29379 __tmp.put_f32_le(self.vibration_y);
29380 __tmp.put_f32_le(self.vibration_z);
29381 __tmp.put_u32_le(self.clipping_0);
29382 __tmp.put_u32_le(self.clipping_1);
29383 __tmp.put_u32_le(self.clipping_2);
29384 if matches!(version, MavlinkVersion::V2) {
29385 let len = __tmp.len();
29386 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29387 } else {
29388 __tmp.len()
29389 }
29390 }
29391}
29392#[doc = "id: 299"]
29393#[doc = "Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
29394#[derive(Debug, Clone, PartialEq)]
29395#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29396#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29397pub struct WIFI_CONFIG_AP_DATA {
29398 #[doc = "Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response."]
29399 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29400 pub ssid: [u8; 32],
29401 #[doc = "Password. Blank for an open AP. MD5 hash when message is sent back as a response."]
29402 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29403 pub password: [u8; 64],
29404 #[doc = "WiFi Mode."]
29405 #[cfg_attr(feature = "serde", serde(default))]
29406 pub mode: WifiConfigApMode,
29407 #[doc = "Message acceptance response (sent back to GS)."]
29408 #[cfg_attr(feature = "serde", serde(default))]
29409 pub response: WifiConfigApResponse,
29410}
29411impl WIFI_CONFIG_AP_DATA {
29412 pub const ENCODED_LEN: usize = 98usize;
29413 pub const DEFAULT: Self = Self {
29414 ssid: [0_u8; 32usize],
29415 password: [0_u8; 64usize],
29416 mode: WifiConfigApMode::DEFAULT,
29417 response: WifiConfigApResponse::DEFAULT,
29418 };
29419 #[cfg(feature = "arbitrary")]
29420 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29421 use arbitrary::{Arbitrary, Unstructured};
29422 let mut buf = [0u8; 1024];
29423 rng.fill_bytes(&mut buf);
29424 let mut unstructured = Unstructured::new(&buf);
29425 Self::arbitrary(&mut unstructured).unwrap_or_default()
29426 }
29427}
29428impl Default for WIFI_CONFIG_AP_DATA {
29429 fn default() -> Self {
29430 Self::DEFAULT.clone()
29431 }
29432}
29433impl MessageData for WIFI_CONFIG_AP_DATA {
29434 type Message = MavMessage;
29435 const ID: u32 = 299u32;
29436 const NAME: &'static str = "WIFI_CONFIG_AP";
29437 const EXTRA_CRC: u8 = 19u8;
29438 const ENCODED_LEN: usize = 98usize;
29439 fn deser(
29440 _version: MavlinkVersion,
29441 __input: &[u8],
29442 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29443 let avail_len = __input.len();
29444 let mut payload_buf = [0; Self::ENCODED_LEN];
29445 let mut buf = if avail_len < Self::ENCODED_LEN {
29446 payload_buf[0..avail_len].copy_from_slice(__input);
29447 Bytes::new(&payload_buf)
29448 } else {
29449 Bytes::new(__input)
29450 };
29451 let mut __struct = Self::default();
29452 for v in &mut __struct.ssid {
29453 let val = buf.get_u8();
29454 *v = val;
29455 }
29456 for v in &mut __struct.password {
29457 let val = buf.get_u8();
29458 *v = val;
29459 }
29460 let tmp = buf.get_i8();
29461 __struct.mode =
29462 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29463 enum_type: "WifiConfigApMode",
29464 value: tmp as u32,
29465 })?;
29466 let tmp = buf.get_i8();
29467 __struct.response =
29468 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29469 enum_type: "WifiConfigApResponse",
29470 value: tmp as u32,
29471 })?;
29472 Ok(__struct)
29473 }
29474 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29475 let mut __tmp = BytesMut::new(bytes);
29476 #[allow(clippy::absurd_extreme_comparisons)]
29477 #[allow(unused_comparisons)]
29478 if __tmp.remaining() < Self::ENCODED_LEN {
29479 panic!(
29480 "buffer is too small (need {} bytes, but got {})",
29481 Self::ENCODED_LEN,
29482 __tmp.remaining(),
29483 )
29484 }
29485 for val in &self.ssid {
29486 __tmp.put_u8(*val);
29487 }
29488 for val in &self.password {
29489 __tmp.put_u8(*val);
29490 }
29491 __tmp.put_i8(self.mode as i8);
29492 __tmp.put_i8(self.response as i8);
29493 if matches!(version, MavlinkVersion::V2) {
29494 let len = __tmp.len();
29495 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29496 } else {
29497 __tmp.len()
29498 }
29499 }
29500}
29501#[doc = "id: 43"]
29502#[doc = "Request the overall list of mission items from the system/component."]
29503#[derive(Debug, Clone, PartialEq)]
29504#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29505#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29506pub struct MISSION_REQUEST_LIST_DATA {
29507 #[doc = "System ID"]
29508 pub target_system: u8,
29509 #[doc = "Component ID"]
29510 pub target_component: u8,
29511 #[doc = "Mission type."]
29512 #[cfg_attr(feature = "serde", serde(default))]
29513 pub mission_type: MavMissionType,
29514}
29515impl MISSION_REQUEST_LIST_DATA {
29516 pub const ENCODED_LEN: usize = 3usize;
29517 pub const DEFAULT: Self = Self {
29518 target_system: 0_u8,
29519 target_component: 0_u8,
29520 mission_type: MavMissionType::DEFAULT,
29521 };
29522 #[cfg(feature = "arbitrary")]
29523 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29524 use arbitrary::{Arbitrary, Unstructured};
29525 let mut buf = [0u8; 1024];
29526 rng.fill_bytes(&mut buf);
29527 let mut unstructured = Unstructured::new(&buf);
29528 Self::arbitrary(&mut unstructured).unwrap_or_default()
29529 }
29530}
29531impl Default for MISSION_REQUEST_LIST_DATA {
29532 fn default() -> Self {
29533 Self::DEFAULT.clone()
29534 }
29535}
29536impl MessageData for MISSION_REQUEST_LIST_DATA {
29537 type Message = MavMessage;
29538 const ID: u32 = 43u32;
29539 const NAME: &'static str = "MISSION_REQUEST_LIST";
29540 const EXTRA_CRC: u8 = 132u8;
29541 const ENCODED_LEN: usize = 3usize;
29542 fn deser(
29543 _version: MavlinkVersion,
29544 __input: &[u8],
29545 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29546 let avail_len = __input.len();
29547 let mut payload_buf = [0; Self::ENCODED_LEN];
29548 let mut buf = if avail_len < Self::ENCODED_LEN {
29549 payload_buf[0..avail_len].copy_from_slice(__input);
29550 Bytes::new(&payload_buf)
29551 } else {
29552 Bytes::new(__input)
29553 };
29554 let mut __struct = Self::default();
29555 __struct.target_system = buf.get_u8();
29556 __struct.target_component = buf.get_u8();
29557 let tmp = buf.get_u8();
29558 __struct.mission_type =
29559 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29560 enum_type: "MavMissionType",
29561 value: tmp as u32,
29562 })?;
29563 Ok(__struct)
29564 }
29565 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29566 let mut __tmp = BytesMut::new(bytes);
29567 #[allow(clippy::absurd_extreme_comparisons)]
29568 #[allow(unused_comparisons)]
29569 if __tmp.remaining() < Self::ENCODED_LEN {
29570 panic!(
29571 "buffer is too small (need {} bytes, but got {})",
29572 Self::ENCODED_LEN,
29573 __tmp.remaining(),
29574 )
29575 }
29576 __tmp.put_u8(self.target_system);
29577 __tmp.put_u8(self.target_component);
29578 __tmp.put_u8(self.mission_type as u8);
29579 if matches!(version, MavlinkVersion::V2) {
29580 let len = __tmp.len();
29581 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29582 } else {
29583 __tmp.len()
29584 }
29585 }
29586}
29587#[doc = "id: 339"]
29588#[doc = "RPM sensor data message."]
29589#[derive(Debug, Clone, PartialEq)]
29590#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29591#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29592pub struct RAW_RPM_DATA {
29593 #[doc = "Indicated rate"]
29594 pub frequency: f32,
29595 #[doc = "Index of this RPM sensor (0-indexed)"]
29596 pub index: u8,
29597}
29598impl RAW_RPM_DATA {
29599 pub const ENCODED_LEN: usize = 5usize;
29600 pub const DEFAULT: Self = Self {
29601 frequency: 0.0_f32,
29602 index: 0_u8,
29603 };
29604 #[cfg(feature = "arbitrary")]
29605 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29606 use arbitrary::{Arbitrary, Unstructured};
29607 let mut buf = [0u8; 1024];
29608 rng.fill_bytes(&mut buf);
29609 let mut unstructured = Unstructured::new(&buf);
29610 Self::arbitrary(&mut unstructured).unwrap_or_default()
29611 }
29612}
29613impl Default for RAW_RPM_DATA {
29614 fn default() -> Self {
29615 Self::DEFAULT.clone()
29616 }
29617}
29618impl MessageData for RAW_RPM_DATA {
29619 type Message = MavMessage;
29620 const ID: u32 = 339u32;
29621 const NAME: &'static str = "RAW_RPM";
29622 const EXTRA_CRC: u8 = 199u8;
29623 const ENCODED_LEN: usize = 5usize;
29624 fn deser(
29625 _version: MavlinkVersion,
29626 __input: &[u8],
29627 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29628 let avail_len = __input.len();
29629 let mut payload_buf = [0; Self::ENCODED_LEN];
29630 let mut buf = if avail_len < Self::ENCODED_LEN {
29631 payload_buf[0..avail_len].copy_from_slice(__input);
29632 Bytes::new(&payload_buf)
29633 } else {
29634 Bytes::new(__input)
29635 };
29636 let mut __struct = Self::default();
29637 __struct.frequency = buf.get_f32_le();
29638 __struct.index = buf.get_u8();
29639 Ok(__struct)
29640 }
29641 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29642 let mut __tmp = BytesMut::new(bytes);
29643 #[allow(clippy::absurd_extreme_comparisons)]
29644 #[allow(unused_comparisons)]
29645 if __tmp.remaining() < Self::ENCODED_LEN {
29646 panic!(
29647 "buffer is too small (need {} bytes, but got {})",
29648 Self::ENCODED_LEN,
29649 __tmp.remaining(),
29650 )
29651 }
29652 __tmp.put_f32_le(self.frequency);
29653 __tmp.put_u8(self.index);
29654 if matches!(version, MavlinkVersion::V2) {
29655 let len = __tmp.len();
29656 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29657 } else {
29658 __tmp.len()
29659 }
29660 }
29661}
29662#[doc = "id: 400"]
29663#[doc = "Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE."]
29664#[derive(Debug, Clone, PartialEq)]
29665#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29666#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29667pub struct PLAY_TUNE_V2_DATA {
29668 #[doc = "Tune format"]
29669 pub format: TuneFormat,
29670 #[doc = "System ID"]
29671 pub target_system: u8,
29672 #[doc = "Component ID"]
29673 pub target_component: u8,
29674 #[doc = "Tune definition as a NULL-terminated string."]
29675 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29676 pub tune: [u8; 248],
29677}
29678impl PLAY_TUNE_V2_DATA {
29679 pub const ENCODED_LEN: usize = 254usize;
29680 pub const DEFAULT: Self = Self {
29681 format: TuneFormat::DEFAULT,
29682 target_system: 0_u8,
29683 target_component: 0_u8,
29684 tune: [0_u8; 248usize],
29685 };
29686 #[cfg(feature = "arbitrary")]
29687 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29688 use arbitrary::{Arbitrary, Unstructured};
29689 let mut buf = [0u8; 1024];
29690 rng.fill_bytes(&mut buf);
29691 let mut unstructured = Unstructured::new(&buf);
29692 Self::arbitrary(&mut unstructured).unwrap_or_default()
29693 }
29694}
29695impl Default for PLAY_TUNE_V2_DATA {
29696 fn default() -> Self {
29697 Self::DEFAULT.clone()
29698 }
29699}
29700impl MessageData for PLAY_TUNE_V2_DATA {
29701 type Message = MavMessage;
29702 const ID: u32 = 400u32;
29703 const NAME: &'static str = "PLAY_TUNE_V2";
29704 const EXTRA_CRC: u8 = 110u8;
29705 const ENCODED_LEN: usize = 254usize;
29706 fn deser(
29707 _version: MavlinkVersion,
29708 __input: &[u8],
29709 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29710 let avail_len = __input.len();
29711 let mut payload_buf = [0; Self::ENCODED_LEN];
29712 let mut buf = if avail_len < Self::ENCODED_LEN {
29713 payload_buf[0..avail_len].copy_from_slice(__input);
29714 Bytes::new(&payload_buf)
29715 } else {
29716 Bytes::new(__input)
29717 };
29718 let mut __struct = Self::default();
29719 let tmp = buf.get_u32_le();
29720 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
29721 ::mavlink_core::error::ParserError::InvalidEnum {
29722 enum_type: "TuneFormat",
29723 value: tmp as u32,
29724 },
29725 )?;
29726 __struct.target_system = buf.get_u8();
29727 __struct.target_component = buf.get_u8();
29728 for v in &mut __struct.tune {
29729 let val = buf.get_u8();
29730 *v = val;
29731 }
29732 Ok(__struct)
29733 }
29734 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29735 let mut __tmp = BytesMut::new(bytes);
29736 #[allow(clippy::absurd_extreme_comparisons)]
29737 #[allow(unused_comparisons)]
29738 if __tmp.remaining() < Self::ENCODED_LEN {
29739 panic!(
29740 "buffer is too small (need {} bytes, but got {})",
29741 Self::ENCODED_LEN,
29742 __tmp.remaining(),
29743 )
29744 }
29745 __tmp.put_u32_le(self.format as u32);
29746 __tmp.put_u8(self.target_system);
29747 __tmp.put_u8(self.target_component);
29748 for val in &self.tune {
29749 __tmp.put_u8(*val);
29750 }
29751 if matches!(version, MavlinkVersion::V2) {
29752 let len = __tmp.len();
29753 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29754 } else {
29755 __tmp.len()
29756 }
29757 }
29758}
29759#[doc = "id: 401"]
29760#[doc = "Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE."]
29761#[derive(Debug, Clone, PartialEq)]
29762#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29763#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29764pub struct SUPPORTED_TUNES_DATA {
29765 #[doc = "Bitfield of supported tune formats."]
29766 pub format: TuneFormat,
29767 #[doc = "System ID"]
29768 pub target_system: u8,
29769 #[doc = "Component ID"]
29770 pub target_component: u8,
29771}
29772impl SUPPORTED_TUNES_DATA {
29773 pub const ENCODED_LEN: usize = 6usize;
29774 pub const DEFAULT: Self = Self {
29775 format: TuneFormat::DEFAULT,
29776 target_system: 0_u8,
29777 target_component: 0_u8,
29778 };
29779 #[cfg(feature = "arbitrary")]
29780 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29781 use arbitrary::{Arbitrary, Unstructured};
29782 let mut buf = [0u8; 1024];
29783 rng.fill_bytes(&mut buf);
29784 let mut unstructured = Unstructured::new(&buf);
29785 Self::arbitrary(&mut unstructured).unwrap_or_default()
29786 }
29787}
29788impl Default for SUPPORTED_TUNES_DATA {
29789 fn default() -> Self {
29790 Self::DEFAULT.clone()
29791 }
29792}
29793impl MessageData for SUPPORTED_TUNES_DATA {
29794 type Message = MavMessage;
29795 const ID: u32 = 401u32;
29796 const NAME: &'static str = "SUPPORTED_TUNES";
29797 const EXTRA_CRC: u8 = 183u8;
29798 const ENCODED_LEN: usize = 6usize;
29799 fn deser(
29800 _version: MavlinkVersion,
29801 __input: &[u8],
29802 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29803 let avail_len = __input.len();
29804 let mut payload_buf = [0; Self::ENCODED_LEN];
29805 let mut buf = if avail_len < Self::ENCODED_LEN {
29806 payload_buf[0..avail_len].copy_from_slice(__input);
29807 Bytes::new(&payload_buf)
29808 } else {
29809 Bytes::new(__input)
29810 };
29811 let mut __struct = Self::default();
29812 let tmp = buf.get_u32_le();
29813 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
29814 ::mavlink_core::error::ParserError::InvalidEnum {
29815 enum_type: "TuneFormat",
29816 value: tmp as u32,
29817 },
29818 )?;
29819 __struct.target_system = buf.get_u8();
29820 __struct.target_component = buf.get_u8();
29821 Ok(__struct)
29822 }
29823 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29824 let mut __tmp = BytesMut::new(bytes);
29825 #[allow(clippy::absurd_extreme_comparisons)]
29826 #[allow(unused_comparisons)]
29827 if __tmp.remaining() < Self::ENCODED_LEN {
29828 panic!(
29829 "buffer is too small (need {} bytes, but got {})",
29830 Self::ENCODED_LEN,
29831 __tmp.remaining(),
29832 )
29833 }
29834 __tmp.put_u32_le(self.format as u32);
29835 __tmp.put_u8(self.target_system);
29836 __tmp.put_u8(self.target_component);
29837 if matches!(version, MavlinkVersion::V2) {
29838 let len = __tmp.len();
29839 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29840 } else {
29841 __tmp.len()
29842 }
29843 }
29844}
29845#[doc = "id: 412"]
29846#[doc = "Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response."]
29847#[derive(Debug, Clone, PartialEq)]
29848#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29849#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29850pub struct REQUEST_EVENT_DATA {
29851 #[doc = "First sequence number of the requested event."]
29852 pub first_sequence: u16,
29853 #[doc = "Last sequence number of the requested event."]
29854 pub last_sequence: u16,
29855 #[doc = "System ID"]
29856 pub target_system: u8,
29857 #[doc = "Component ID"]
29858 pub target_component: u8,
29859}
29860impl REQUEST_EVENT_DATA {
29861 pub const ENCODED_LEN: usize = 6usize;
29862 pub const DEFAULT: Self = Self {
29863 first_sequence: 0_u16,
29864 last_sequence: 0_u16,
29865 target_system: 0_u8,
29866 target_component: 0_u8,
29867 };
29868 #[cfg(feature = "arbitrary")]
29869 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29870 use arbitrary::{Arbitrary, Unstructured};
29871 let mut buf = [0u8; 1024];
29872 rng.fill_bytes(&mut buf);
29873 let mut unstructured = Unstructured::new(&buf);
29874 Self::arbitrary(&mut unstructured).unwrap_or_default()
29875 }
29876}
29877impl Default for REQUEST_EVENT_DATA {
29878 fn default() -> Self {
29879 Self::DEFAULT.clone()
29880 }
29881}
29882impl MessageData for REQUEST_EVENT_DATA {
29883 type Message = MavMessage;
29884 const ID: u32 = 412u32;
29885 const NAME: &'static str = "REQUEST_EVENT";
29886 const EXTRA_CRC: u8 = 33u8;
29887 const ENCODED_LEN: usize = 6usize;
29888 fn deser(
29889 _version: MavlinkVersion,
29890 __input: &[u8],
29891 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29892 let avail_len = __input.len();
29893 let mut payload_buf = [0; Self::ENCODED_LEN];
29894 let mut buf = if avail_len < Self::ENCODED_LEN {
29895 payload_buf[0..avail_len].copy_from_slice(__input);
29896 Bytes::new(&payload_buf)
29897 } else {
29898 Bytes::new(__input)
29899 };
29900 let mut __struct = Self::default();
29901 __struct.first_sequence = buf.get_u16_le();
29902 __struct.last_sequence = buf.get_u16_le();
29903 __struct.target_system = buf.get_u8();
29904 __struct.target_component = buf.get_u8();
29905 Ok(__struct)
29906 }
29907 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29908 let mut __tmp = BytesMut::new(bytes);
29909 #[allow(clippy::absurd_extreme_comparisons)]
29910 #[allow(unused_comparisons)]
29911 if __tmp.remaining() < Self::ENCODED_LEN {
29912 panic!(
29913 "buffer is too small (need {} bytes, but got {})",
29914 Self::ENCODED_LEN,
29915 __tmp.remaining(),
29916 )
29917 }
29918 __tmp.put_u16_le(self.first_sequence);
29919 __tmp.put_u16_le(self.last_sequence);
29920 __tmp.put_u8(self.target_system);
29921 __tmp.put_u8(self.target_component);
29922 if matches!(version, MavlinkVersion::V2) {
29923 let len = __tmp.len();
29924 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29925 } else {
29926 __tmp.len()
29927 }
29928 }
29929}
29930#[doc = "id: 29"]
29931#[doc = "The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field."]
29932#[derive(Debug, Clone, PartialEq)]
29933#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29934#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29935pub struct SCALED_PRESSURE_DATA {
29936 #[doc = "Timestamp (time since system boot)."]
29937 pub time_boot_ms: u32,
29938 #[doc = "Absolute pressure"]
29939 pub press_abs: f32,
29940 #[doc = "Differential pressure 1"]
29941 pub press_diff: f32,
29942 #[doc = "Absolute pressure temperature"]
29943 pub temperature: i16,
29944 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
29945 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29946 pub temperature_press_diff: i16,
29947}
29948impl SCALED_PRESSURE_DATA {
29949 pub const ENCODED_LEN: usize = 16usize;
29950 pub const DEFAULT: Self = Self {
29951 time_boot_ms: 0_u32,
29952 press_abs: 0.0_f32,
29953 press_diff: 0.0_f32,
29954 temperature: 0_i16,
29955 temperature_press_diff: 0_i16,
29956 };
29957 #[cfg(feature = "arbitrary")]
29958 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29959 use arbitrary::{Arbitrary, Unstructured};
29960 let mut buf = [0u8; 1024];
29961 rng.fill_bytes(&mut buf);
29962 let mut unstructured = Unstructured::new(&buf);
29963 Self::arbitrary(&mut unstructured).unwrap_or_default()
29964 }
29965}
29966impl Default for SCALED_PRESSURE_DATA {
29967 fn default() -> Self {
29968 Self::DEFAULT.clone()
29969 }
29970}
29971impl MessageData for SCALED_PRESSURE_DATA {
29972 type Message = MavMessage;
29973 const ID: u32 = 29u32;
29974 const NAME: &'static str = "SCALED_PRESSURE";
29975 const EXTRA_CRC: u8 = 115u8;
29976 const ENCODED_LEN: usize = 16usize;
29977 fn deser(
29978 _version: MavlinkVersion,
29979 __input: &[u8],
29980 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29981 let avail_len = __input.len();
29982 let mut payload_buf = [0; Self::ENCODED_LEN];
29983 let mut buf = if avail_len < Self::ENCODED_LEN {
29984 payload_buf[0..avail_len].copy_from_slice(__input);
29985 Bytes::new(&payload_buf)
29986 } else {
29987 Bytes::new(__input)
29988 };
29989 let mut __struct = Self::default();
29990 __struct.time_boot_ms = buf.get_u32_le();
29991 __struct.press_abs = buf.get_f32_le();
29992 __struct.press_diff = buf.get_f32_le();
29993 __struct.temperature = buf.get_i16_le();
29994 __struct.temperature_press_diff = buf.get_i16_le();
29995 Ok(__struct)
29996 }
29997 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29998 let mut __tmp = BytesMut::new(bytes);
29999 #[allow(clippy::absurd_extreme_comparisons)]
30000 #[allow(unused_comparisons)]
30001 if __tmp.remaining() < Self::ENCODED_LEN {
30002 panic!(
30003 "buffer is too small (need {} bytes, but got {})",
30004 Self::ENCODED_LEN,
30005 __tmp.remaining(),
30006 )
30007 }
30008 __tmp.put_u32_le(self.time_boot_ms);
30009 __tmp.put_f32_le(self.press_abs);
30010 __tmp.put_f32_le(self.press_diff);
30011 __tmp.put_i16_le(self.temperature);
30012 __tmp.put_i16_le(self.temperature_press_diff);
30013 if matches!(version, MavlinkVersion::V2) {
30014 let len = __tmp.len();
30015 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30016 } else {
30017 __tmp.len()
30018 }
30019 }
30020}
30021#[doc = "id: 143"]
30022#[doc = "Barometer readings for 3rd barometer."]
30023#[derive(Debug, Clone, PartialEq)]
30024#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30025#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30026pub struct SCALED_PRESSURE3_DATA {
30027 #[doc = "Timestamp (time since system boot)."]
30028 pub time_boot_ms: u32,
30029 #[doc = "Absolute pressure"]
30030 pub press_abs: f32,
30031 #[doc = "Differential pressure"]
30032 pub press_diff: f32,
30033 #[doc = "Absolute pressure temperature"]
30034 pub temperature: i16,
30035 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
30036 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30037 pub temperature_press_diff: i16,
30038}
30039impl SCALED_PRESSURE3_DATA {
30040 pub const ENCODED_LEN: usize = 16usize;
30041 pub const DEFAULT: Self = Self {
30042 time_boot_ms: 0_u32,
30043 press_abs: 0.0_f32,
30044 press_diff: 0.0_f32,
30045 temperature: 0_i16,
30046 temperature_press_diff: 0_i16,
30047 };
30048 #[cfg(feature = "arbitrary")]
30049 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30050 use arbitrary::{Arbitrary, Unstructured};
30051 let mut buf = [0u8; 1024];
30052 rng.fill_bytes(&mut buf);
30053 let mut unstructured = Unstructured::new(&buf);
30054 Self::arbitrary(&mut unstructured).unwrap_or_default()
30055 }
30056}
30057impl Default for SCALED_PRESSURE3_DATA {
30058 fn default() -> Self {
30059 Self::DEFAULT.clone()
30060 }
30061}
30062impl MessageData for SCALED_PRESSURE3_DATA {
30063 type Message = MavMessage;
30064 const ID: u32 = 143u32;
30065 const NAME: &'static str = "SCALED_PRESSURE3";
30066 const EXTRA_CRC: u8 = 131u8;
30067 const ENCODED_LEN: usize = 16usize;
30068 fn deser(
30069 _version: MavlinkVersion,
30070 __input: &[u8],
30071 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30072 let avail_len = __input.len();
30073 let mut payload_buf = [0; Self::ENCODED_LEN];
30074 let mut buf = if avail_len < Self::ENCODED_LEN {
30075 payload_buf[0..avail_len].copy_from_slice(__input);
30076 Bytes::new(&payload_buf)
30077 } else {
30078 Bytes::new(__input)
30079 };
30080 let mut __struct = Self::default();
30081 __struct.time_boot_ms = buf.get_u32_le();
30082 __struct.press_abs = buf.get_f32_le();
30083 __struct.press_diff = buf.get_f32_le();
30084 __struct.temperature = buf.get_i16_le();
30085 __struct.temperature_press_diff = buf.get_i16_le();
30086 Ok(__struct)
30087 }
30088 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30089 let mut __tmp = BytesMut::new(bytes);
30090 #[allow(clippy::absurd_extreme_comparisons)]
30091 #[allow(unused_comparisons)]
30092 if __tmp.remaining() < Self::ENCODED_LEN {
30093 panic!(
30094 "buffer is too small (need {} bytes, but got {})",
30095 Self::ENCODED_LEN,
30096 __tmp.remaining(),
30097 )
30098 }
30099 __tmp.put_u32_le(self.time_boot_ms);
30100 __tmp.put_f32_le(self.press_abs);
30101 __tmp.put_f32_le(self.press_diff);
30102 __tmp.put_i16_le(self.temperature);
30103 __tmp.put_i16_le(self.temperature_press_diff);
30104 if matches!(version, MavlinkVersion::V2) {
30105 let len = __tmp.len();
30106 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30107 } else {
30108 __tmp.len()
30109 }
30110 }
30111}
30112#[doc = "id: 283"]
30113#[doc = "Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.."]
30114#[derive(Debug, Clone, PartialEq)]
30115#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30116#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30117pub struct GIMBAL_DEVICE_INFORMATION_DATA {
30118 #[doc = "UID of gimbal hardware (0 if unknown)."]
30119 pub uid: u64,
30120 #[doc = "Timestamp (time since system boot)."]
30121 pub time_boot_ms: u32,
30122 #[doc = "0xff)."]
30123 pub firmware_version: u32,
30124 #[doc = "0xff)."]
30125 pub hardware_version: u32,
30126 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
30127 pub roll_min: f32,
30128 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
30129 pub roll_max: f32,
30130 #[doc = "Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
30131 pub pitch_min: f32,
30132 #[doc = "Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
30133 pub pitch_max: f32,
30134 #[doc = "Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
30135 pub yaw_min: f32,
30136 #[doc = "Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
30137 pub yaw_max: f32,
30138 #[doc = "Bitmap of gimbal capability flags."]
30139 pub cap_flags: GimbalDeviceCapFlags,
30140 #[doc = "Bitmap for use for gimbal-specific capability flags."]
30141 pub custom_cap_flags: u16,
30142 #[doc = "Name of the gimbal vendor."]
30143 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30144 pub vendor_name: [u8; 32],
30145 #[doc = "Name of the gimbal model."]
30146 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30147 pub model_name: [u8; 32],
30148 #[doc = "Custom name of the gimbal given to it by the user."]
30149 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30150 pub custom_name: [u8; 32],
30151 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
30152 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30153 pub gimbal_device_id: u8,
30154}
30155impl GIMBAL_DEVICE_INFORMATION_DATA {
30156 pub const ENCODED_LEN: usize = 145usize;
30157 pub const DEFAULT: Self = Self {
30158 uid: 0_u64,
30159 time_boot_ms: 0_u32,
30160 firmware_version: 0_u32,
30161 hardware_version: 0_u32,
30162 roll_min: 0.0_f32,
30163 roll_max: 0.0_f32,
30164 pitch_min: 0.0_f32,
30165 pitch_max: 0.0_f32,
30166 yaw_min: 0.0_f32,
30167 yaw_max: 0.0_f32,
30168 cap_flags: GimbalDeviceCapFlags::DEFAULT,
30169 custom_cap_flags: 0_u16,
30170 vendor_name: [0_u8; 32usize],
30171 model_name: [0_u8; 32usize],
30172 custom_name: [0_u8; 32usize],
30173 gimbal_device_id: 0_u8,
30174 };
30175 #[cfg(feature = "arbitrary")]
30176 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30177 use arbitrary::{Arbitrary, Unstructured};
30178 let mut buf = [0u8; 1024];
30179 rng.fill_bytes(&mut buf);
30180 let mut unstructured = Unstructured::new(&buf);
30181 Self::arbitrary(&mut unstructured).unwrap_or_default()
30182 }
30183}
30184impl Default for GIMBAL_DEVICE_INFORMATION_DATA {
30185 fn default() -> Self {
30186 Self::DEFAULT.clone()
30187 }
30188}
30189impl MessageData for GIMBAL_DEVICE_INFORMATION_DATA {
30190 type Message = MavMessage;
30191 const ID: u32 = 283u32;
30192 const NAME: &'static str = "GIMBAL_DEVICE_INFORMATION";
30193 const EXTRA_CRC: u8 = 74u8;
30194 const ENCODED_LEN: usize = 145usize;
30195 fn deser(
30196 _version: MavlinkVersion,
30197 __input: &[u8],
30198 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30199 let avail_len = __input.len();
30200 let mut payload_buf = [0; Self::ENCODED_LEN];
30201 let mut buf = if avail_len < Self::ENCODED_LEN {
30202 payload_buf[0..avail_len].copy_from_slice(__input);
30203 Bytes::new(&payload_buf)
30204 } else {
30205 Bytes::new(__input)
30206 };
30207 let mut __struct = Self::default();
30208 __struct.uid = buf.get_u64_le();
30209 __struct.time_boot_ms = buf.get_u32_le();
30210 __struct.firmware_version = buf.get_u32_le();
30211 __struct.hardware_version = buf.get_u32_le();
30212 __struct.roll_min = buf.get_f32_le();
30213 __struct.roll_max = buf.get_f32_le();
30214 __struct.pitch_min = buf.get_f32_le();
30215 __struct.pitch_max = buf.get_f32_le();
30216 __struct.yaw_min = buf.get_f32_le();
30217 __struct.yaw_max = buf.get_f32_le();
30218 let tmp = buf.get_u16_le();
30219 __struct.cap_flags = GimbalDeviceCapFlags::from_bits(
30220 tmp & GimbalDeviceCapFlags::all().bits(),
30221 )
30222 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30223 flag_type: "GimbalDeviceCapFlags",
30224 value: tmp as u32,
30225 })?;
30226 __struct.custom_cap_flags = buf.get_u16_le();
30227 for v in &mut __struct.vendor_name {
30228 let val = buf.get_u8();
30229 *v = val;
30230 }
30231 for v in &mut __struct.model_name {
30232 let val = buf.get_u8();
30233 *v = val;
30234 }
30235 for v in &mut __struct.custom_name {
30236 let val = buf.get_u8();
30237 *v = val;
30238 }
30239 __struct.gimbal_device_id = buf.get_u8();
30240 Ok(__struct)
30241 }
30242 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30243 let mut __tmp = BytesMut::new(bytes);
30244 #[allow(clippy::absurd_extreme_comparisons)]
30245 #[allow(unused_comparisons)]
30246 if __tmp.remaining() < Self::ENCODED_LEN {
30247 panic!(
30248 "buffer is too small (need {} bytes, but got {})",
30249 Self::ENCODED_LEN,
30250 __tmp.remaining(),
30251 )
30252 }
30253 __tmp.put_u64_le(self.uid);
30254 __tmp.put_u32_le(self.time_boot_ms);
30255 __tmp.put_u32_le(self.firmware_version);
30256 __tmp.put_u32_le(self.hardware_version);
30257 __tmp.put_f32_le(self.roll_min);
30258 __tmp.put_f32_le(self.roll_max);
30259 __tmp.put_f32_le(self.pitch_min);
30260 __tmp.put_f32_le(self.pitch_max);
30261 __tmp.put_f32_le(self.yaw_min);
30262 __tmp.put_f32_le(self.yaw_max);
30263 __tmp.put_u16_le(self.cap_flags.bits());
30264 __tmp.put_u16_le(self.custom_cap_flags);
30265 for val in &self.vendor_name {
30266 __tmp.put_u8(*val);
30267 }
30268 for val in &self.model_name {
30269 __tmp.put_u8(*val);
30270 }
30271 for val in &self.custom_name {
30272 __tmp.put_u8(*val);
30273 }
30274 __tmp.put_u8(self.gimbal_device_id);
30275 if matches!(version, MavlinkVersion::V2) {
30276 let len = __tmp.len();
30277 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30278 } else {
30279 __tmp.len()
30280 }
30281 }
30282}
30283#[doc = "id: 38"]
30284#[doc = "This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!."]
30285#[derive(Debug, Clone, PartialEq)]
30286#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30287#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30288pub struct MISSION_WRITE_PARTIAL_LIST_DATA {
30289 #[doc = "Start index. Must be smaller / equal to the largest index of the current onboard list."]
30290 pub start_index: i16,
30291 #[doc = "End index, equal or greater than start index."]
30292 pub end_index: i16,
30293 #[doc = "System ID"]
30294 pub target_system: u8,
30295 #[doc = "Component ID"]
30296 pub target_component: u8,
30297 #[doc = "Mission type."]
30298 #[cfg_attr(feature = "serde", serde(default))]
30299 pub mission_type: MavMissionType,
30300}
30301impl MISSION_WRITE_PARTIAL_LIST_DATA {
30302 pub const ENCODED_LEN: usize = 7usize;
30303 pub const DEFAULT: Self = Self {
30304 start_index: 0_i16,
30305 end_index: 0_i16,
30306 target_system: 0_u8,
30307 target_component: 0_u8,
30308 mission_type: MavMissionType::DEFAULT,
30309 };
30310 #[cfg(feature = "arbitrary")]
30311 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30312 use arbitrary::{Arbitrary, Unstructured};
30313 let mut buf = [0u8; 1024];
30314 rng.fill_bytes(&mut buf);
30315 let mut unstructured = Unstructured::new(&buf);
30316 Self::arbitrary(&mut unstructured).unwrap_or_default()
30317 }
30318}
30319impl Default for MISSION_WRITE_PARTIAL_LIST_DATA {
30320 fn default() -> Self {
30321 Self::DEFAULT.clone()
30322 }
30323}
30324impl MessageData for MISSION_WRITE_PARTIAL_LIST_DATA {
30325 type Message = MavMessage;
30326 const ID: u32 = 38u32;
30327 const NAME: &'static str = "MISSION_WRITE_PARTIAL_LIST";
30328 const EXTRA_CRC: u8 = 9u8;
30329 const ENCODED_LEN: usize = 7usize;
30330 fn deser(
30331 _version: MavlinkVersion,
30332 __input: &[u8],
30333 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30334 let avail_len = __input.len();
30335 let mut payload_buf = [0; Self::ENCODED_LEN];
30336 let mut buf = if avail_len < Self::ENCODED_LEN {
30337 payload_buf[0..avail_len].copy_from_slice(__input);
30338 Bytes::new(&payload_buf)
30339 } else {
30340 Bytes::new(__input)
30341 };
30342 let mut __struct = Self::default();
30343 __struct.start_index = buf.get_i16_le();
30344 __struct.end_index = buf.get_i16_le();
30345 __struct.target_system = buf.get_u8();
30346 __struct.target_component = buf.get_u8();
30347 let tmp = buf.get_u8();
30348 __struct.mission_type =
30349 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30350 enum_type: "MavMissionType",
30351 value: tmp as u32,
30352 })?;
30353 Ok(__struct)
30354 }
30355 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30356 let mut __tmp = BytesMut::new(bytes);
30357 #[allow(clippy::absurd_extreme_comparisons)]
30358 #[allow(unused_comparisons)]
30359 if __tmp.remaining() < Self::ENCODED_LEN {
30360 panic!(
30361 "buffer is too small (need {} bytes, but got {})",
30362 Self::ENCODED_LEN,
30363 __tmp.remaining(),
30364 )
30365 }
30366 __tmp.put_i16_le(self.start_index);
30367 __tmp.put_i16_le(self.end_index);
30368 __tmp.put_u8(self.target_system);
30369 __tmp.put_u8(self.target_component);
30370 __tmp.put_u8(self.mission_type as u8);
30371 if matches!(version, MavlinkVersion::V2) {
30372 let len = __tmp.len();
30373 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30374 } else {
30375 __tmp.len()
30376 }
30377 }
30378}
30379#[doc = "id: 12919"]
30380#[doc = "Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location."]
30381#[derive(Debug, Clone, PartialEq)]
30382#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30383#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30384pub struct OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
30385 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
30386 pub operator_latitude: i32,
30387 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
30388 pub operator_longitude: i32,
30389 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
30390 pub operator_altitude_geo: f32,
30391 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
30392 pub timestamp: u32,
30393 #[doc = "System ID (0 for broadcast)."]
30394 pub target_system: u8,
30395 #[doc = "Component ID (0 for broadcast)."]
30396 pub target_component: u8,
30397}
30398impl OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
30399 pub const ENCODED_LEN: usize = 18usize;
30400 pub const DEFAULT: Self = Self {
30401 operator_latitude: 0_i32,
30402 operator_longitude: 0_i32,
30403 operator_altitude_geo: 0.0_f32,
30404 timestamp: 0_u32,
30405 target_system: 0_u8,
30406 target_component: 0_u8,
30407 };
30408 #[cfg(feature = "arbitrary")]
30409 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30410 use arbitrary::{Arbitrary, Unstructured};
30411 let mut buf = [0u8; 1024];
30412 rng.fill_bytes(&mut buf);
30413 let mut unstructured = Unstructured::new(&buf);
30414 Self::arbitrary(&mut unstructured).unwrap_or_default()
30415 }
30416}
30417impl Default for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
30418 fn default() -> Self {
30419 Self::DEFAULT.clone()
30420 }
30421}
30422impl MessageData for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
30423 type Message = MavMessage;
30424 const ID: u32 = 12919u32;
30425 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM_UPDATE";
30426 const EXTRA_CRC: u8 = 7u8;
30427 const ENCODED_LEN: usize = 18usize;
30428 fn deser(
30429 _version: MavlinkVersion,
30430 __input: &[u8],
30431 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30432 let avail_len = __input.len();
30433 let mut payload_buf = [0; Self::ENCODED_LEN];
30434 let mut buf = if avail_len < Self::ENCODED_LEN {
30435 payload_buf[0..avail_len].copy_from_slice(__input);
30436 Bytes::new(&payload_buf)
30437 } else {
30438 Bytes::new(__input)
30439 };
30440 let mut __struct = Self::default();
30441 __struct.operator_latitude = buf.get_i32_le();
30442 __struct.operator_longitude = buf.get_i32_le();
30443 __struct.operator_altitude_geo = buf.get_f32_le();
30444 __struct.timestamp = buf.get_u32_le();
30445 __struct.target_system = buf.get_u8();
30446 __struct.target_component = buf.get_u8();
30447 Ok(__struct)
30448 }
30449 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30450 let mut __tmp = BytesMut::new(bytes);
30451 #[allow(clippy::absurd_extreme_comparisons)]
30452 #[allow(unused_comparisons)]
30453 if __tmp.remaining() < Self::ENCODED_LEN {
30454 panic!(
30455 "buffer is too small (need {} bytes, but got {})",
30456 Self::ENCODED_LEN,
30457 __tmp.remaining(),
30458 )
30459 }
30460 __tmp.put_i32_le(self.operator_latitude);
30461 __tmp.put_i32_le(self.operator_longitude);
30462 __tmp.put_f32_le(self.operator_altitude_geo);
30463 __tmp.put_u32_le(self.timestamp);
30464 __tmp.put_u8(self.target_system);
30465 __tmp.put_u8(self.target_component);
30466 if matches!(version, MavlinkVersion::V2) {
30467 let len = __tmp.len();
30468 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30469 } else {
30470 __tmp.len()
30471 }
30472 }
30473}
30474#[doc = "id: 411"]
30475#[doc = "Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events."]
30476#[derive(Debug, Clone, PartialEq)]
30477#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30478#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30479pub struct CURRENT_EVENT_SEQUENCE_DATA {
30480 #[doc = "Sequence number."]
30481 pub sequence: u16,
30482 #[doc = "Flag bitset."]
30483 pub flags: MavEventCurrentSequenceFlags,
30484}
30485impl CURRENT_EVENT_SEQUENCE_DATA {
30486 pub const ENCODED_LEN: usize = 3usize;
30487 pub const DEFAULT: Self = Self {
30488 sequence: 0_u16,
30489 flags: MavEventCurrentSequenceFlags::DEFAULT,
30490 };
30491 #[cfg(feature = "arbitrary")]
30492 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30493 use arbitrary::{Arbitrary, Unstructured};
30494 let mut buf = [0u8; 1024];
30495 rng.fill_bytes(&mut buf);
30496 let mut unstructured = Unstructured::new(&buf);
30497 Self::arbitrary(&mut unstructured).unwrap_or_default()
30498 }
30499}
30500impl Default for CURRENT_EVENT_SEQUENCE_DATA {
30501 fn default() -> Self {
30502 Self::DEFAULT.clone()
30503 }
30504}
30505impl MessageData for CURRENT_EVENT_SEQUENCE_DATA {
30506 type Message = MavMessage;
30507 const ID: u32 = 411u32;
30508 const NAME: &'static str = "CURRENT_EVENT_SEQUENCE";
30509 const EXTRA_CRC: u8 = 106u8;
30510 const ENCODED_LEN: usize = 3usize;
30511 fn deser(
30512 _version: MavlinkVersion,
30513 __input: &[u8],
30514 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30515 let avail_len = __input.len();
30516 let mut payload_buf = [0; Self::ENCODED_LEN];
30517 let mut buf = if avail_len < Self::ENCODED_LEN {
30518 payload_buf[0..avail_len].copy_from_slice(__input);
30519 Bytes::new(&payload_buf)
30520 } else {
30521 Bytes::new(__input)
30522 };
30523 let mut __struct = Self::default();
30524 __struct.sequence = buf.get_u16_le();
30525 let tmp = buf.get_u8();
30526 __struct.flags =
30527 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30528 enum_type: "MavEventCurrentSequenceFlags",
30529 value: tmp as u32,
30530 })?;
30531 Ok(__struct)
30532 }
30533 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30534 let mut __tmp = BytesMut::new(bytes);
30535 #[allow(clippy::absurd_extreme_comparisons)]
30536 #[allow(unused_comparisons)]
30537 if __tmp.remaining() < Self::ENCODED_LEN {
30538 panic!(
30539 "buffer is too small (need {} bytes, but got {})",
30540 Self::ENCODED_LEN,
30541 __tmp.remaining(),
30542 )
30543 }
30544 __tmp.put_u16_le(self.sequence);
30545 __tmp.put_u8(self.flags as u8);
30546 if matches!(version, MavlinkVersion::V2) {
30547 let len = __tmp.len();
30548 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30549 } else {
30550 __tmp.len()
30551 }
30552 }
30553}
30554#[doc = "id: 332"]
30555#[doc = "Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED)."]
30556#[derive(Debug, Clone, PartialEq)]
30557#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30558#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30559pub struct TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
30560 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
30561 pub time_usec: u64,
30562 #[doc = "X-coordinate of waypoint, set to NaN if not being used"]
30563 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30564 pub pos_x: [f32; 5],
30565 #[doc = "Y-coordinate of waypoint, set to NaN if not being used"]
30566 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30567 pub pos_y: [f32; 5],
30568 #[doc = "Z-coordinate of waypoint, set to NaN if not being used"]
30569 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30570 pub pos_z: [f32; 5],
30571 #[doc = "X-velocity of waypoint, set to NaN if not being used"]
30572 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30573 pub vel_x: [f32; 5],
30574 #[doc = "Y-velocity of waypoint, set to NaN if not being used"]
30575 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30576 pub vel_y: [f32; 5],
30577 #[doc = "Z-velocity of waypoint, set to NaN if not being used"]
30578 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30579 pub vel_z: [f32; 5],
30580 #[doc = "X-acceleration of waypoint, set to NaN if not being used"]
30581 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30582 pub acc_x: [f32; 5],
30583 #[doc = "Y-acceleration of waypoint, set to NaN if not being used"]
30584 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30585 pub acc_y: [f32; 5],
30586 #[doc = "Z-acceleration of waypoint, set to NaN if not being used"]
30587 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30588 pub acc_z: [f32; 5],
30589 #[doc = "Yaw angle, set to NaN if not being used"]
30590 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30591 pub pos_yaw: [f32; 5],
30592 #[doc = "Yaw rate, set to NaN if not being used"]
30593 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30594 pub vel_yaw: [f32; 5],
30595 #[doc = "MAV_CMD command id of waypoint, set to UINT16_MAX if not being used."]
30596 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30597 pub command: [u16; 5],
30598 #[doc = "Number of valid points (up-to 5 waypoints are possible)"]
30599 pub valid_points: u8,
30600}
30601impl TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
30602 pub const ENCODED_LEN: usize = 239usize;
30603 pub const DEFAULT: Self = Self {
30604 time_usec: 0_u64,
30605 pos_x: [0.0_f32; 5usize],
30606 pos_y: [0.0_f32; 5usize],
30607 pos_z: [0.0_f32; 5usize],
30608 vel_x: [0.0_f32; 5usize],
30609 vel_y: [0.0_f32; 5usize],
30610 vel_z: [0.0_f32; 5usize],
30611 acc_x: [0.0_f32; 5usize],
30612 acc_y: [0.0_f32; 5usize],
30613 acc_z: [0.0_f32; 5usize],
30614 pos_yaw: [0.0_f32; 5usize],
30615 vel_yaw: [0.0_f32; 5usize],
30616 command: [0_u16; 5usize],
30617 valid_points: 0_u8,
30618 };
30619 #[cfg(feature = "arbitrary")]
30620 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30621 use arbitrary::{Arbitrary, Unstructured};
30622 let mut buf = [0u8; 1024];
30623 rng.fill_bytes(&mut buf);
30624 let mut unstructured = Unstructured::new(&buf);
30625 Self::arbitrary(&mut unstructured).unwrap_or_default()
30626 }
30627}
30628impl Default for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
30629 fn default() -> Self {
30630 Self::DEFAULT.clone()
30631 }
30632}
30633impl MessageData for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
30634 type Message = MavMessage;
30635 const ID: u32 = 332u32;
30636 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_WAYPOINTS";
30637 const EXTRA_CRC: u8 = 236u8;
30638 const ENCODED_LEN: usize = 239usize;
30639 fn deser(
30640 _version: MavlinkVersion,
30641 __input: &[u8],
30642 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30643 let avail_len = __input.len();
30644 let mut payload_buf = [0; Self::ENCODED_LEN];
30645 let mut buf = if avail_len < Self::ENCODED_LEN {
30646 payload_buf[0..avail_len].copy_from_slice(__input);
30647 Bytes::new(&payload_buf)
30648 } else {
30649 Bytes::new(__input)
30650 };
30651 let mut __struct = Self::default();
30652 __struct.time_usec = buf.get_u64_le();
30653 for v in &mut __struct.pos_x {
30654 let val = buf.get_f32_le();
30655 *v = val;
30656 }
30657 for v in &mut __struct.pos_y {
30658 let val = buf.get_f32_le();
30659 *v = val;
30660 }
30661 for v in &mut __struct.pos_z {
30662 let val = buf.get_f32_le();
30663 *v = val;
30664 }
30665 for v in &mut __struct.vel_x {
30666 let val = buf.get_f32_le();
30667 *v = val;
30668 }
30669 for v in &mut __struct.vel_y {
30670 let val = buf.get_f32_le();
30671 *v = val;
30672 }
30673 for v in &mut __struct.vel_z {
30674 let val = buf.get_f32_le();
30675 *v = val;
30676 }
30677 for v in &mut __struct.acc_x {
30678 let val = buf.get_f32_le();
30679 *v = val;
30680 }
30681 for v in &mut __struct.acc_y {
30682 let val = buf.get_f32_le();
30683 *v = val;
30684 }
30685 for v in &mut __struct.acc_z {
30686 let val = buf.get_f32_le();
30687 *v = val;
30688 }
30689 for v in &mut __struct.pos_yaw {
30690 let val = buf.get_f32_le();
30691 *v = val;
30692 }
30693 for v in &mut __struct.vel_yaw {
30694 let val = buf.get_f32_le();
30695 *v = val;
30696 }
30697 for v in &mut __struct.command {
30698 let val = buf.get_u16_le();
30699 *v = val;
30700 }
30701 __struct.valid_points = buf.get_u8();
30702 Ok(__struct)
30703 }
30704 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30705 let mut __tmp = BytesMut::new(bytes);
30706 #[allow(clippy::absurd_extreme_comparisons)]
30707 #[allow(unused_comparisons)]
30708 if __tmp.remaining() < Self::ENCODED_LEN {
30709 panic!(
30710 "buffer is too small (need {} bytes, but got {})",
30711 Self::ENCODED_LEN,
30712 __tmp.remaining(),
30713 )
30714 }
30715 __tmp.put_u64_le(self.time_usec);
30716 for val in &self.pos_x {
30717 __tmp.put_f32_le(*val);
30718 }
30719 for val in &self.pos_y {
30720 __tmp.put_f32_le(*val);
30721 }
30722 for val in &self.pos_z {
30723 __tmp.put_f32_le(*val);
30724 }
30725 for val in &self.vel_x {
30726 __tmp.put_f32_le(*val);
30727 }
30728 for val in &self.vel_y {
30729 __tmp.put_f32_le(*val);
30730 }
30731 for val in &self.vel_z {
30732 __tmp.put_f32_le(*val);
30733 }
30734 for val in &self.acc_x {
30735 __tmp.put_f32_le(*val);
30736 }
30737 for val in &self.acc_y {
30738 __tmp.put_f32_le(*val);
30739 }
30740 for val in &self.acc_z {
30741 __tmp.put_f32_le(*val);
30742 }
30743 for val in &self.pos_yaw {
30744 __tmp.put_f32_le(*val);
30745 }
30746 for val in &self.vel_yaw {
30747 __tmp.put_f32_le(*val);
30748 }
30749 for val in &self.command {
30750 __tmp.put_u16_le(*val);
30751 }
30752 __tmp.put_u8(self.valid_points);
30753 if matches!(version, MavlinkVersion::V2) {
30754 let len = __tmp.len();
30755 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30756 } else {
30757 __tmp.len()
30758 }
30759 }
30760}
30761#[doc = "id: 86"]
30762#[doc = "Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system)."]
30763#[derive(Debug, Clone, PartialEq)]
30764#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30765#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30766pub struct SET_POSITION_TARGET_GLOBAL_INT_DATA {
30767 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
30768 pub time_boot_ms: u32,
30769 #[doc = "Latitude in WGS84 frame"]
30770 pub lat_int: i32,
30771 #[doc = "Longitude in WGS84 frame"]
30772 pub lon_int: i32,
30773 #[doc = "Altitude (MSL, Relative to home, or AGL - depending on frame)"]
30774 pub alt: f32,
30775 #[doc = "X velocity in NED frame"]
30776 pub vx: f32,
30777 #[doc = "Y velocity in NED frame"]
30778 pub vy: f32,
30779 #[doc = "Z velocity in NED frame"]
30780 pub vz: f32,
30781 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
30782 pub afx: f32,
30783 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
30784 pub afy: f32,
30785 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
30786 pub afz: f32,
30787 #[doc = "yaw setpoint"]
30788 pub yaw: f32,
30789 #[doc = "yaw rate setpoint"]
30790 pub yaw_rate: f32,
30791 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
30792 pub type_mask: PositionTargetTypemask,
30793 #[doc = "System ID"]
30794 pub target_system: u8,
30795 #[doc = "Component ID"]
30796 pub target_component: u8,
30797 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
30798 pub coordinate_frame: MavFrame,
30799}
30800impl SET_POSITION_TARGET_GLOBAL_INT_DATA {
30801 pub const ENCODED_LEN: usize = 53usize;
30802 pub const DEFAULT: Self = Self {
30803 time_boot_ms: 0_u32,
30804 lat_int: 0_i32,
30805 lon_int: 0_i32,
30806 alt: 0.0_f32,
30807 vx: 0.0_f32,
30808 vy: 0.0_f32,
30809 vz: 0.0_f32,
30810 afx: 0.0_f32,
30811 afy: 0.0_f32,
30812 afz: 0.0_f32,
30813 yaw: 0.0_f32,
30814 yaw_rate: 0.0_f32,
30815 type_mask: PositionTargetTypemask::DEFAULT,
30816 target_system: 0_u8,
30817 target_component: 0_u8,
30818 coordinate_frame: MavFrame::DEFAULT,
30819 };
30820 #[cfg(feature = "arbitrary")]
30821 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30822 use arbitrary::{Arbitrary, Unstructured};
30823 let mut buf = [0u8; 1024];
30824 rng.fill_bytes(&mut buf);
30825 let mut unstructured = Unstructured::new(&buf);
30826 Self::arbitrary(&mut unstructured).unwrap_or_default()
30827 }
30828}
30829impl Default for SET_POSITION_TARGET_GLOBAL_INT_DATA {
30830 fn default() -> Self {
30831 Self::DEFAULT.clone()
30832 }
30833}
30834impl MessageData for SET_POSITION_TARGET_GLOBAL_INT_DATA {
30835 type Message = MavMessage;
30836 const ID: u32 = 86u32;
30837 const NAME: &'static str = "SET_POSITION_TARGET_GLOBAL_INT";
30838 const EXTRA_CRC: u8 = 5u8;
30839 const ENCODED_LEN: usize = 53usize;
30840 fn deser(
30841 _version: MavlinkVersion,
30842 __input: &[u8],
30843 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30844 let avail_len = __input.len();
30845 let mut payload_buf = [0; Self::ENCODED_LEN];
30846 let mut buf = if avail_len < Self::ENCODED_LEN {
30847 payload_buf[0..avail_len].copy_from_slice(__input);
30848 Bytes::new(&payload_buf)
30849 } else {
30850 Bytes::new(__input)
30851 };
30852 let mut __struct = Self::default();
30853 __struct.time_boot_ms = buf.get_u32_le();
30854 __struct.lat_int = buf.get_i32_le();
30855 __struct.lon_int = buf.get_i32_le();
30856 __struct.alt = buf.get_f32_le();
30857 __struct.vx = buf.get_f32_le();
30858 __struct.vy = buf.get_f32_le();
30859 __struct.vz = buf.get_f32_le();
30860 __struct.afx = buf.get_f32_le();
30861 __struct.afy = buf.get_f32_le();
30862 __struct.afz = buf.get_f32_le();
30863 __struct.yaw = buf.get_f32_le();
30864 __struct.yaw_rate = buf.get_f32_le();
30865 let tmp = buf.get_u16_le();
30866 __struct.type_mask = PositionTargetTypemask::from_bits(
30867 tmp & PositionTargetTypemask::all().bits(),
30868 )
30869 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30870 flag_type: "PositionTargetTypemask",
30871 value: tmp as u32,
30872 })?;
30873 __struct.target_system = buf.get_u8();
30874 __struct.target_component = buf.get_u8();
30875 let tmp = buf.get_u8();
30876 __struct.coordinate_frame =
30877 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30878 enum_type: "MavFrame",
30879 value: tmp as u32,
30880 })?;
30881 Ok(__struct)
30882 }
30883 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30884 let mut __tmp = BytesMut::new(bytes);
30885 #[allow(clippy::absurd_extreme_comparisons)]
30886 #[allow(unused_comparisons)]
30887 if __tmp.remaining() < Self::ENCODED_LEN {
30888 panic!(
30889 "buffer is too small (need {} bytes, but got {})",
30890 Self::ENCODED_LEN,
30891 __tmp.remaining(),
30892 )
30893 }
30894 __tmp.put_u32_le(self.time_boot_ms);
30895 __tmp.put_i32_le(self.lat_int);
30896 __tmp.put_i32_le(self.lon_int);
30897 __tmp.put_f32_le(self.alt);
30898 __tmp.put_f32_le(self.vx);
30899 __tmp.put_f32_le(self.vy);
30900 __tmp.put_f32_le(self.vz);
30901 __tmp.put_f32_le(self.afx);
30902 __tmp.put_f32_le(self.afy);
30903 __tmp.put_f32_le(self.afz);
30904 __tmp.put_f32_le(self.yaw);
30905 __tmp.put_f32_le(self.yaw_rate);
30906 __tmp.put_u16_le(self.type_mask.bits());
30907 __tmp.put_u8(self.target_system);
30908 __tmp.put_u8(self.target_component);
30909 __tmp.put_u8(self.coordinate_frame as u8);
30910 if matches!(version, MavlinkVersion::V2) {
30911 let len = __tmp.len();
30912 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30913 } else {
30914 __tmp.len()
30915 }
30916 }
30917}
30918#[derive(Clone, PartialEq, Debug)]
30919#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30920#[cfg_attr(feature = "serde", serde(tag = "type"))]
30921#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30922#[repr(u32)]
30923pub enum MavMessage {
30924 MANUAL_CONTROL(MANUAL_CONTROL_DATA),
30925 V2_EXTENSION(V2_EXTENSION_DATA),
30926 GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA),
30927 OPTICAL_FLOW(OPTICAL_FLOW_DATA),
30928 TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA),
30929 HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA),
30930 OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA),
30931 ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA),
30932 GENERATOR_STATUS(GENERATOR_STATUS_DATA),
30933 FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA),
30934 ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA),
30935 COMPONENT_INFORMATION_BASIC(COMPONENT_INFORMATION_BASIC_DATA),
30936 FUEL_STATUS(FUEL_STATUS_DATA),
30937 OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA),
30938 ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA),
30939 MISSION_CURRENT(MISSION_CURRENT_DATA),
30940 GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA),
30941 GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA),
30942 SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA),
30943 PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA),
30944 COLLISION(COLLISION_DATA),
30945 GPS2_RTK(GPS2_RTK_DATA),
30946 COMMAND_INT(COMMAND_INT_DATA),
30947 OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA),
30948 LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA),
30949 HIL_SENSOR(HIL_SENSOR_DATA),
30950 SET_MODE(SET_MODE_DATA),
30951 RAW_PRESSURE(RAW_PRESSURE_DATA),
30952 TIMESYNC(TIMESYNC_DATA),
30953 REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA),
30954 HIL_GPS(HIL_GPS_DATA),
30955 CAN_FRAME(CAN_FRAME_DATA),
30956 HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA),
30957 COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA),
30958 TERRAIN_REPORT(TERRAIN_REPORT_DATA),
30959 SCALED_PRESSURE2(SCALED_PRESSURE2_DATA),
30960 CAMERA_INFORMATION(CAMERA_INFORMATION_DATA),
30961 HIGH_LATENCY2(HIGH_LATENCY2_DATA),
30962 ADSB_VEHICLE(ADSB_VEHICLE_DATA),
30963 VFR_HUD(VFR_HUD_DATA),
30964 ALTITUDE(ALTITUDE_DATA),
30965 MISSION_REQUEST(MISSION_REQUEST_DATA),
30966 CANFD_FRAME(CANFD_FRAME_DATA),
30967 NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA),
30968 HIL_CONTROLS(HIL_CONTROLS_DATA),
30969 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA),
30970 VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA),
30971 COMMAND_CANCEL(COMMAND_CANCEL_DATA),
30972 CAMERA_SETTINGS(CAMERA_SETTINGS_DATA),
30973 GPS_STATUS(GPS_STATUS_DATA),
30974 ATTITUDE(ATTITUDE_DATA),
30975 ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA),
30976 CELLULAR_STATUS(CELLULAR_STATUS_DATA),
30977 ESC_STATUS(ESC_STATUS_DATA),
30978 RAW_IMU(RAW_IMU_DATA),
30979 HIGH_LATENCY(HIGH_LATENCY_DATA),
30980 AVAILABLE_MODES_MONITOR(AVAILABLE_MODES_MONITOR_DATA),
30981 ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA),
30982 MISSION_ITEM_INT(MISSION_ITEM_INT_DATA),
30983 CURRENT_MODE(CURRENT_MODE_DATA),
30984 SCALED_IMU(SCALED_IMU_DATA),
30985 SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA),
30986 TERRAIN_CHECK(TERRAIN_CHECK_DATA),
30987 DATA_STREAM(DATA_STREAM_DATA),
30988 LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA),
30989 EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA),
30990 CAMERA_TRIGGER(CAMERA_TRIGGER_DATA),
30991 MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA),
30992 GPS_INJECT_DATA(GPS_INJECT_DATA_DATA),
30993 HOME_POSITION(HOME_POSITION_DATA),
30994 PARAM_MAP_RC(PARAM_MAP_RC_DATA),
30995 SERIAL_CONTROL(SERIAL_CONTROL_DATA),
30996 OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA),
30997 MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA),
30998 MANUAL_SETPOINT(MANUAL_SETPOINT_DATA),
30999 FENCE_STATUS(FENCE_STATUS_DATA),
31000 FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA),
31001 GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA),
31002 GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA),
31003 RESOURCE_REQUEST(RESOURCE_REQUEST_DATA),
31004 MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA),
31005 PARAM_SET(PARAM_SET_DATA),
31006 LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA),
31007 CAMERA_THERMAL_RANGE(CAMERA_THERMAL_RANGE_DATA),
31008 RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA),
31009 SCALED_IMU3(SCALED_IMU3_DATA),
31010 CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA),
31011 PARAM_EXT_SET(PARAM_EXT_SET_DATA),
31012 ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA),
31013 ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA),
31014 HIGHRES_IMU(HIGHRES_IMU_DATA),
31015 OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA),
31016 MISSION_ACK(MISSION_ACK_DATA),
31017 GPS_RTCM_DATA(GPS_RTCM_DATA_DATA),
31018 RADIO_STATUS(RADIO_STATUS_DATA),
31019 AUTH_KEY(AUTH_KEY_DATA),
31020 RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA),
31021 LOG_DATA(LOG_DATA_DATA),
31022 PARAM_VALUE(PARAM_VALUE_DATA),
31023 ATT_POS_MOCAP(ATT_POS_MOCAP_DATA),
31024 SET_HOME_POSITION(SET_HOME_POSITION_DATA),
31025 COMPONENT_METADATA(COMPONENT_METADATA_DATA),
31026 WINCH_STATUS(WINCH_STATUS_DATA),
31027 TERRAIN_DATA(TERRAIN_DATA_DATA),
31028 DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA),
31029 ESC_INFO(ESC_INFO_DATA),
31030 SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA),
31031 PROTOCOL_VERSION(PROTOCOL_VERSION_DATA),
31032 MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA),
31033 SCALED_IMU2(SCALED_IMU2_DATA),
31034 DISTANCE_SENSOR(DISTANCE_SENSOR_DATA),
31035 SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA),
31036 ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA),
31037 EVENT(EVENT_DATA),
31038 GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA),
31039 PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA),
31040 STATUSTEXT(STATUSTEXT_DATA),
31041 CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA),
31042 EFI_STATUS(EFI_STATUS_DATA),
31043 LOG_REQUEST_END(LOG_REQUEST_END_DATA),
31044 GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA),
31045 UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA),
31046 GPS_RTK(GPS_RTK_DATA),
31047 MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA),
31048 PING(PING_DATA),
31049 DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA),
31050 SETUP_SIGNING(SETUP_SIGNING_DATA),
31051 CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA),
31052 BATTERY_STATUS(BATTERY_STATUS_DATA),
31053 MISSION_COUNT(MISSION_COUNT_DATA),
31054 OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA),
31055 RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA),
31056 TERRAIN_REQUEST(TERRAIN_REQUEST_DATA),
31057 OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA),
31058 LANDING_TARGET(LANDING_TARGET_DATA),
31059 FOLLOW_TARGET(FOLLOW_TARGET_DATA),
31060 GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA),
31061 CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA),
31062 GPS_INPUT(GPS_INPUT_DATA),
31063 PLAY_TUNE(PLAY_TUNE_DATA),
31064 HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA),
31065 VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA),
31066 CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA),
31067 MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA),
31068 LOGGING_DATA(LOGGING_DATA_DATA),
31069 ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA),
31070 LOG_ERASE(LOG_ERASE_DATA),
31071 WHEEL_DISTANCE(WHEEL_DISTANCE_DATA),
31072 PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA),
31073 RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA),
31074 ATTITUDE_TARGET(ATTITUDE_TARGET_DATA),
31075 ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA),
31076 HIL_STATE(HIL_STATE_DATA),
31077 AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA),
31078 UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA),
31079 HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA),
31080 MISSION_ITEM(MISSION_ITEM_DATA),
31081 UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA),
31082 COMMAND_ACK(COMMAND_ACK_DATA),
31083 WIND_COV(WIND_COV_DATA),
31084 DEBUG(DEBUG_DATA),
31085 LOGGING_ACK(LOGGING_ACK_DATA),
31086 AVAILABLE_MODES(AVAILABLE_MODES_DATA),
31087 STORAGE_INFORMATION(STORAGE_INFORMATION_DATA),
31088 CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA),
31089 OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA),
31090 ODOMETRY(ODOMETRY_DATA),
31091 SYSTEM_TIME(SYSTEM_TIME_DATA),
31092 VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA),
31093 CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA),
31094 OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA),
31095 SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA),
31096 PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA),
31097 LINK_NODE_STATUS(LINK_NODE_STATUS_DATA),
31098 OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA),
31099 NAMED_VALUE_INT(NAMED_VALUE_INT_DATA),
31100 BATTERY_INFO(BATTERY_INFO_DATA),
31101 GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA),
31102 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA),
31103 HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA),
31104 DEBUG_VECT(DEBUG_VECT_DATA),
31105 VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA),
31106 GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA),
31107 SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA),
31108 PARAM_EXT_ACK(PARAM_EXT_ACK_DATA),
31109 SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA),
31110 COMMAND_LONG(COMMAND_LONG_DATA),
31111 MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA),
31112 POWER_STATUS(POWER_STATUS_DATA),
31113 CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA),
31114 GPS_RAW_INT(GPS_RAW_INT_DATA),
31115 SIM_STATE(SIM_STATE_DATA),
31116 CELLULAR_CONFIG(CELLULAR_CONFIG_DATA),
31117 LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA),
31118 CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA),
31119 TUNNEL(TUNNEL_DATA),
31120 RC_CHANNELS(RC_CHANNELS_DATA),
31121 NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA),
31122 SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA),
31123 POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA),
31124 MEMORY_VECT(MEMORY_VECT_DATA),
31125 PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA),
31126 POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA),
31127 BUTTON_CHANGE(BUTTON_CHANGE_DATA),
31128 LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA),
31129 LOG_ENTRY(LOG_ENTRY_DATA),
31130 GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA),
31131 AIS_VESSEL(AIS_VESSEL_DATA),
31132 TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA),
31133 MAG_CAL_REPORT(MAG_CAL_REPORT_DATA),
31134 GPS2_RAW(GPS2_RAW_DATA),
31135 HEARTBEAT(HEARTBEAT_DATA),
31136 SYS_STATUS(SYS_STATUS_DATA),
31137 VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA),
31138 VIBRATION(VIBRATION_DATA),
31139 WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA),
31140 MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA),
31141 RAW_RPM(RAW_RPM_DATA),
31142 PLAY_TUNE_V2(PLAY_TUNE_V2_DATA),
31143 SUPPORTED_TUNES(SUPPORTED_TUNES_DATA),
31144 REQUEST_EVENT(REQUEST_EVENT_DATA),
31145 SCALED_PRESSURE(SCALED_PRESSURE_DATA),
31146 SCALED_PRESSURE3(SCALED_PRESSURE3_DATA),
31147 GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA),
31148 MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA),
31149 OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA),
31150 CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA),
31151 TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA),
31152 SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA),
31153}
31154impl MavMessage {
31155 pub const fn all_ids() -> &'static [u32] {
31156 &[
31157 0u32, 1u32, 2u32, 4u32, 5u32, 6u32, 7u32, 8u32, 11u32, 20u32, 21u32, 22u32, 23u32,
31158 24u32, 25u32, 26u32, 27u32, 28u32, 29u32, 30u32, 31u32, 32u32, 33u32, 34u32, 35u32,
31159 36u32, 37u32, 38u32, 39u32, 40u32, 41u32, 42u32, 43u32, 44u32, 45u32, 46u32, 47u32,
31160 48u32, 49u32, 50u32, 51u32, 54u32, 55u32, 61u32, 62u32, 63u32, 64u32, 65u32, 66u32,
31161 67u32, 69u32, 70u32, 73u32, 74u32, 75u32, 76u32, 77u32, 80u32, 81u32, 82u32, 83u32,
31162 84u32, 85u32, 86u32, 87u32, 89u32, 90u32, 91u32, 92u32, 93u32, 100u32, 101u32, 102u32,
31163 103u32, 104u32, 105u32, 106u32, 107u32, 108u32, 109u32, 110u32, 111u32, 112u32, 113u32,
31164 114u32, 115u32, 116u32, 117u32, 118u32, 119u32, 120u32, 121u32, 122u32, 123u32, 124u32,
31165 125u32, 126u32, 127u32, 128u32, 129u32, 130u32, 131u32, 132u32, 133u32, 134u32, 135u32,
31166 136u32, 137u32, 138u32, 139u32, 140u32, 141u32, 142u32, 143u32, 144u32, 146u32, 147u32,
31167 148u32, 149u32, 162u32, 192u32, 225u32, 230u32, 231u32, 232u32, 233u32, 234u32, 235u32,
31168 241u32, 242u32, 243u32, 244u32, 245u32, 246u32, 247u32, 248u32, 249u32, 250u32, 251u32,
31169 252u32, 253u32, 254u32, 256u32, 257u32, 258u32, 259u32, 260u32, 261u32, 262u32, 263u32,
31170 264u32, 265u32, 266u32, 267u32, 268u32, 269u32, 270u32, 271u32, 275u32, 276u32, 277u32,
31171 280u32, 281u32, 282u32, 283u32, 284u32, 285u32, 286u32, 287u32, 288u32, 290u32, 291u32,
31172 299u32, 300u32, 301u32, 310u32, 311u32, 320u32, 321u32, 322u32, 323u32, 324u32, 330u32,
31173 331u32, 332u32, 333u32, 334u32, 335u32, 336u32, 339u32, 340u32, 350u32, 360u32, 370u32,
31174 371u32, 372u32, 373u32, 375u32, 380u32, 385u32, 386u32, 387u32, 388u32, 390u32, 395u32,
31175 396u32, 397u32, 400u32, 401u32, 410u32, 411u32, 412u32, 413u32, 435u32, 436u32, 437u32,
31176 440u32, 9000u32, 9005u32, 12900u32, 12901u32, 12902u32, 12903u32, 12904u32, 12905u32,
31177 12915u32, 12918u32, 12919u32, 12920u32,
31178 ]
31179 }
31180}
31181impl Message for MavMessage {
31182 fn parse(
31183 version: MavlinkVersion,
31184 id: u32,
31185 payload: &[u8],
31186 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31187 match id {
31188 MANUAL_CONTROL_DATA::ID => {
31189 MANUAL_CONTROL_DATA::deser(version, payload).map(Self::MANUAL_CONTROL)
31190 }
31191 V2_EXTENSION_DATA::ID => {
31192 V2_EXTENSION_DATA::deser(version, payload).map(Self::V2_EXTENSION)
31193 }
31194 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
31195 GLOBAL_VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
31196 .map(Self::GLOBAL_VISION_POSITION_ESTIMATE)
31197 }
31198 OPTICAL_FLOW_DATA::ID => {
31199 OPTICAL_FLOW_DATA::deser(version, payload).map(Self::OPTICAL_FLOW)
31200 }
31201 TIME_ESTIMATE_TO_TARGET_DATA::ID => {
31202 TIME_ESTIMATE_TO_TARGET_DATA::deser(version, payload)
31203 .map(Self::TIME_ESTIMATE_TO_TARGET)
31204 }
31205 HIL_RC_INPUTS_RAW_DATA::ID => {
31206 HIL_RC_INPUTS_RAW_DATA::deser(version, payload).map(Self::HIL_RC_INPUTS_RAW)
31207 }
31208 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => {
31209 OPEN_DRONE_ID_MESSAGE_PACK_DATA::deser(version, payload)
31210 .map(Self::OPEN_DRONE_ID_MESSAGE_PACK)
31211 }
31212 ATTITUDE_QUATERNION_COV_DATA::ID => {
31213 ATTITUDE_QUATERNION_COV_DATA::deser(version, payload)
31214 .map(Self::ATTITUDE_QUATERNION_COV)
31215 }
31216 GENERATOR_STATUS_DATA::ID => {
31217 GENERATOR_STATUS_DATA::deser(version, payload).map(Self::GENERATOR_STATUS)
31218 }
31219 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::deser(version, payload)
31220 .map(Self::FILE_TRANSFER_PROTOCOL),
31221 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::deser(version, payload)
31222 .map(Self::ACTUATOR_OUTPUT_STATUS),
31223 COMPONENT_INFORMATION_BASIC_DATA::ID => {
31224 COMPONENT_INFORMATION_BASIC_DATA::deser(version, payload)
31225 .map(Self::COMPONENT_INFORMATION_BASIC)
31226 }
31227 FUEL_STATUS_DATA::ID => {
31228 FUEL_STATUS_DATA::deser(version, payload).map(Self::FUEL_STATUS)
31229 }
31230 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::deser(version, payload)
31231 .map(Self::OPEN_DRONE_ID_BASIC_ID),
31232 ESTIMATOR_STATUS_DATA::ID => {
31233 ESTIMATOR_STATUS_DATA::deser(version, payload).map(Self::ESTIMATOR_STATUS)
31234 }
31235 MISSION_CURRENT_DATA::ID => {
31236 MISSION_CURRENT_DATA::deser(version, payload).map(Self::MISSION_CURRENT)
31237 }
31238 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => {
31239 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::deser(version, payload)
31240 .map(Self::GIMBAL_DEVICE_ATTITUDE_STATUS)
31241 }
31242 GLOBAL_POSITION_INT_DATA::ID => {
31243 GLOBAL_POSITION_INT_DATA::deser(version, payload).map(Self::GLOBAL_POSITION_INT)
31244 }
31245 SET_ATTITUDE_TARGET_DATA::ID => {
31246 SET_ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::SET_ATTITUDE_TARGET)
31247 }
31248 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::deser(version, payload)
31249 .map(Self::PARAM_EXT_REQUEST_READ),
31250 COLLISION_DATA::ID => COLLISION_DATA::deser(version, payload).map(Self::COLLISION),
31251 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::deser(version, payload).map(Self::GPS2_RTK),
31252 COMMAND_INT_DATA::ID => {
31253 COMMAND_INT_DATA::deser(version, payload).map(Self::COMMAND_INT)
31254 }
31255 OPEN_DRONE_ID_SELF_ID_DATA::ID => {
31256 OPEN_DRONE_ID_SELF_ID_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SELF_ID)
31257 }
31258 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::deser(version, payload)
31259 .map(Self::LOCAL_POSITION_NED_COV),
31260 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::deser(version, payload).map(Self::HIL_SENSOR),
31261 SET_MODE_DATA::ID => SET_MODE_DATA::deser(version, payload).map(Self::SET_MODE),
31262 RAW_PRESSURE_DATA::ID => {
31263 RAW_PRESSURE_DATA::deser(version, payload).map(Self::RAW_PRESSURE)
31264 }
31265 TIMESYNC_DATA::ID => TIMESYNC_DATA::deser(version, payload).map(Self::TIMESYNC),
31266 REQUEST_DATA_STREAM_DATA::ID => {
31267 REQUEST_DATA_STREAM_DATA::deser(version, payload).map(Self::REQUEST_DATA_STREAM)
31268 }
31269 HIL_GPS_DATA::ID => HIL_GPS_DATA::deser(version, payload).map(Self::HIL_GPS),
31270 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::deser(version, payload).map(Self::CAN_FRAME),
31271 HYGROMETER_SENSOR_DATA::ID => {
31272 HYGROMETER_SENSOR_DATA::deser(version, payload).map(Self::HYGROMETER_SENSOR)
31273 }
31274 COMPONENT_INFORMATION_DATA::ID => {
31275 COMPONENT_INFORMATION_DATA::deser(version, payload).map(Self::COMPONENT_INFORMATION)
31276 }
31277 TERRAIN_REPORT_DATA::ID => {
31278 TERRAIN_REPORT_DATA::deser(version, payload).map(Self::TERRAIN_REPORT)
31279 }
31280 SCALED_PRESSURE2_DATA::ID => {
31281 SCALED_PRESSURE2_DATA::deser(version, payload).map(Self::SCALED_PRESSURE2)
31282 }
31283 CAMERA_INFORMATION_DATA::ID => {
31284 CAMERA_INFORMATION_DATA::deser(version, payload).map(Self::CAMERA_INFORMATION)
31285 }
31286 HIGH_LATENCY2_DATA::ID => {
31287 HIGH_LATENCY2_DATA::deser(version, payload).map(Self::HIGH_LATENCY2)
31288 }
31289 ADSB_VEHICLE_DATA::ID => {
31290 ADSB_VEHICLE_DATA::deser(version, payload).map(Self::ADSB_VEHICLE)
31291 }
31292 VFR_HUD_DATA::ID => VFR_HUD_DATA::deser(version, payload).map(Self::VFR_HUD),
31293 ALTITUDE_DATA::ID => ALTITUDE_DATA::deser(version, payload).map(Self::ALTITUDE),
31294 MISSION_REQUEST_DATA::ID => {
31295 MISSION_REQUEST_DATA::deser(version, payload).map(Self::MISSION_REQUEST)
31296 }
31297 CANFD_FRAME_DATA::ID => {
31298 CANFD_FRAME_DATA::deser(version, payload).map(Self::CANFD_FRAME)
31299 }
31300 NAV_CONTROLLER_OUTPUT_DATA::ID => {
31301 NAV_CONTROLLER_OUTPUT_DATA::deser(version, payload).map(Self::NAV_CONTROLLER_OUTPUT)
31302 }
31303 HIL_CONTROLS_DATA::ID => {
31304 HIL_CONTROLS_DATA::deser(version, payload).map(Self::HIL_CONTROLS)
31305 }
31306 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
31307 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::deser(version, payload)
31308 .map(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE)
31309 }
31310 VISION_POSITION_ESTIMATE_DATA::ID => {
31311 VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
31312 .map(Self::VISION_POSITION_ESTIMATE)
31313 }
31314 COMMAND_CANCEL_DATA::ID => {
31315 COMMAND_CANCEL_DATA::deser(version, payload).map(Self::COMMAND_CANCEL)
31316 }
31317 CAMERA_SETTINGS_DATA::ID => {
31318 CAMERA_SETTINGS_DATA::deser(version, payload).map(Self::CAMERA_SETTINGS)
31319 }
31320 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::deser(version, payload).map(Self::GPS_STATUS),
31321 ATTITUDE_DATA::ID => ATTITUDE_DATA::deser(version, payload).map(Self::ATTITUDE),
31322 ENCAPSULATED_DATA_DATA::ID => {
31323 ENCAPSULATED_DATA_DATA::deser(version, payload).map(Self::ENCAPSULATED_DATA)
31324 }
31325 CELLULAR_STATUS_DATA::ID => {
31326 CELLULAR_STATUS_DATA::deser(version, payload).map(Self::CELLULAR_STATUS)
31327 }
31328 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::deser(version, payload).map(Self::ESC_STATUS),
31329 RAW_IMU_DATA::ID => RAW_IMU_DATA::deser(version, payload).map(Self::RAW_IMU),
31330 HIGH_LATENCY_DATA::ID => {
31331 HIGH_LATENCY_DATA::deser(version, payload).map(Self::HIGH_LATENCY)
31332 }
31333 AVAILABLE_MODES_MONITOR_DATA::ID => {
31334 AVAILABLE_MODES_MONITOR_DATA::deser(version, payload)
31335 .map(Self::AVAILABLE_MODES_MONITOR)
31336 }
31337 ILLUMINATOR_STATUS_DATA::ID => {
31338 ILLUMINATOR_STATUS_DATA::deser(version, payload).map(Self::ILLUMINATOR_STATUS)
31339 }
31340 MISSION_ITEM_INT_DATA::ID => {
31341 MISSION_ITEM_INT_DATA::deser(version, payload).map(Self::MISSION_ITEM_INT)
31342 }
31343 CURRENT_MODE_DATA::ID => {
31344 CURRENT_MODE_DATA::deser(version, payload).map(Self::CURRENT_MODE)
31345 }
31346 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::deser(version, payload).map(Self::SCALED_IMU),
31347 SAFETY_ALLOWED_AREA_DATA::ID => {
31348 SAFETY_ALLOWED_AREA_DATA::deser(version, payload).map(Self::SAFETY_ALLOWED_AREA)
31349 }
31350 TERRAIN_CHECK_DATA::ID => {
31351 TERRAIN_CHECK_DATA::deser(version, payload).map(Self::TERRAIN_CHECK)
31352 }
31353 DATA_STREAM_DATA::ID => {
31354 DATA_STREAM_DATA::deser(version, payload).map(Self::DATA_STREAM)
31355 }
31356 LOG_REQUEST_LIST_DATA::ID => {
31357 LOG_REQUEST_LIST_DATA::deser(version, payload).map(Self::LOG_REQUEST_LIST)
31358 }
31359 EXTENDED_SYS_STATE_DATA::ID => {
31360 EXTENDED_SYS_STATE_DATA::deser(version, payload).map(Self::EXTENDED_SYS_STATE)
31361 }
31362 CAMERA_TRIGGER_DATA::ID => {
31363 CAMERA_TRIGGER_DATA::deser(version, payload).map(Self::CAMERA_TRIGGER)
31364 }
31365 MESSAGE_INTERVAL_DATA::ID => {
31366 MESSAGE_INTERVAL_DATA::deser(version, payload).map(Self::MESSAGE_INTERVAL)
31367 }
31368 GPS_INJECT_DATA_DATA::ID => {
31369 GPS_INJECT_DATA_DATA::deser(version, payload).map(Self::GPS_INJECT_DATA)
31370 }
31371 HOME_POSITION_DATA::ID => {
31372 HOME_POSITION_DATA::deser(version, payload).map(Self::HOME_POSITION)
31373 }
31374 PARAM_MAP_RC_DATA::ID => {
31375 PARAM_MAP_RC_DATA::deser(version, payload).map(Self::PARAM_MAP_RC)
31376 }
31377 SERIAL_CONTROL_DATA::ID => {
31378 SERIAL_CONTROL_DATA::deser(version, payload).map(Self::SERIAL_CONTROL)
31379 }
31380 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::deser(version, payload)
31381 .map(Self::OPEN_DRONE_ID_LOCATION),
31382 MISSION_SET_CURRENT_DATA::ID => {
31383 MISSION_SET_CURRENT_DATA::deser(version, payload).map(Self::MISSION_SET_CURRENT)
31384 }
31385 MANUAL_SETPOINT_DATA::ID => {
31386 MANUAL_SETPOINT_DATA::deser(version, payload).map(Self::MANUAL_SETPOINT)
31387 }
31388 FENCE_STATUS_DATA::ID => {
31389 FENCE_STATUS_DATA::deser(version, payload).map(Self::FENCE_STATUS)
31390 }
31391 FLIGHT_INFORMATION_DATA::ID => {
31392 FLIGHT_INFORMATION_DATA::deser(version, payload).map(Self::FLIGHT_INFORMATION)
31393 }
31394 GIMBAL_MANAGER_INFORMATION_DATA::ID => {
31395 GIMBAL_MANAGER_INFORMATION_DATA::deser(version, payload)
31396 .map(Self::GIMBAL_MANAGER_INFORMATION)
31397 }
31398 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => {
31399 GIMBAL_MANAGER_SET_ATTITUDE_DATA::deser(version, payload)
31400 .map(Self::GIMBAL_MANAGER_SET_ATTITUDE)
31401 }
31402 RESOURCE_REQUEST_DATA::ID => {
31403 RESOURCE_REQUEST_DATA::deser(version, payload).map(Self::RESOURCE_REQUEST)
31404 }
31405 MISSION_CLEAR_ALL_DATA::ID => {
31406 MISSION_CLEAR_ALL_DATA::deser(version, payload).map(Self::MISSION_CLEAR_ALL)
31407 }
31408 PARAM_SET_DATA::ID => PARAM_SET_DATA::deser(version, payload).map(Self::PARAM_SET),
31409 LOG_REQUEST_DATA_DATA::ID => {
31410 LOG_REQUEST_DATA_DATA::deser(version, payload).map(Self::LOG_REQUEST_DATA)
31411 }
31412 CAMERA_THERMAL_RANGE_DATA::ID => {
31413 CAMERA_THERMAL_RANGE_DATA::deser(version, payload).map(Self::CAMERA_THERMAL_RANGE)
31414 }
31415 RESPONSE_EVENT_ERROR_DATA::ID => {
31416 RESPONSE_EVENT_ERROR_DATA::deser(version, payload).map(Self::RESPONSE_EVENT_ERROR)
31417 }
31418 SCALED_IMU3_DATA::ID => {
31419 SCALED_IMU3_DATA::deser(version, payload).map(Self::SCALED_IMU3)
31420 }
31421 CAMERA_CAPTURE_STATUS_DATA::ID => {
31422 CAMERA_CAPTURE_STATUS_DATA::deser(version, payload).map(Self::CAMERA_CAPTURE_STATUS)
31423 }
31424 PARAM_EXT_SET_DATA::ID => {
31425 PARAM_EXT_SET_DATA::deser(version, payload).map(Self::PARAM_EXT_SET)
31426 }
31427 ACTUATOR_CONTROL_TARGET_DATA::ID => {
31428 ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
31429 .map(Self::ACTUATOR_CONTROL_TARGET)
31430 }
31431 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::deser(version, payload)
31432 .map(Self::ORBIT_EXECUTION_STATUS),
31433 HIGHRES_IMU_DATA::ID => {
31434 HIGHRES_IMU_DATA::deser(version, payload).map(Self::HIGHRES_IMU)
31435 }
31436 OPEN_DRONE_ID_SYSTEM_DATA::ID => {
31437 OPEN_DRONE_ID_SYSTEM_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SYSTEM)
31438 }
31439 MISSION_ACK_DATA::ID => {
31440 MISSION_ACK_DATA::deser(version, payload).map(Self::MISSION_ACK)
31441 }
31442 GPS_RTCM_DATA_DATA::ID => {
31443 GPS_RTCM_DATA_DATA::deser(version, payload).map(Self::GPS_RTCM_DATA)
31444 }
31445 RADIO_STATUS_DATA::ID => {
31446 RADIO_STATUS_DATA::deser(version, payload).map(Self::RADIO_STATUS)
31447 }
31448 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::deser(version, payload).map(Self::AUTH_KEY),
31449 RC_CHANNELS_RAW_DATA::ID => {
31450 RC_CHANNELS_RAW_DATA::deser(version, payload).map(Self::RC_CHANNELS_RAW)
31451 }
31452 LOG_DATA_DATA::ID => LOG_DATA_DATA::deser(version, payload).map(Self::LOG_DATA),
31453 PARAM_VALUE_DATA::ID => {
31454 PARAM_VALUE_DATA::deser(version, payload).map(Self::PARAM_VALUE)
31455 }
31456 ATT_POS_MOCAP_DATA::ID => {
31457 ATT_POS_MOCAP_DATA::deser(version, payload).map(Self::ATT_POS_MOCAP)
31458 }
31459 SET_HOME_POSITION_DATA::ID => {
31460 SET_HOME_POSITION_DATA::deser(version, payload).map(Self::SET_HOME_POSITION)
31461 }
31462 COMPONENT_METADATA_DATA::ID => {
31463 COMPONENT_METADATA_DATA::deser(version, payload).map(Self::COMPONENT_METADATA)
31464 }
31465 WINCH_STATUS_DATA::ID => {
31466 WINCH_STATUS_DATA::deser(version, payload).map(Self::WINCH_STATUS)
31467 }
31468 TERRAIN_DATA_DATA::ID => {
31469 TERRAIN_DATA_DATA::deser(version, payload).map(Self::TERRAIN_DATA)
31470 }
31471 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => {
31472 DATA_TRANSMISSION_HANDSHAKE_DATA::deser(version, payload)
31473 .map(Self::DATA_TRANSMISSION_HANDSHAKE)
31474 }
31475 ESC_INFO_DATA::ID => ESC_INFO_DATA::deser(version, payload).map(Self::ESC_INFO),
31476 SERVO_OUTPUT_RAW_DATA::ID => {
31477 SERVO_OUTPUT_RAW_DATA::deser(version, payload).map(Self::SERVO_OUTPUT_RAW)
31478 }
31479 PROTOCOL_VERSION_DATA::ID => {
31480 PROTOCOL_VERSION_DATA::deser(version, payload).map(Self::PROTOCOL_VERSION)
31481 }
31482 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => {
31483 MISSION_REQUEST_PARTIAL_LIST_DATA::deser(version, payload)
31484 .map(Self::MISSION_REQUEST_PARTIAL_LIST)
31485 }
31486 SCALED_IMU2_DATA::ID => {
31487 SCALED_IMU2_DATA::deser(version, payload).map(Self::SCALED_IMU2)
31488 }
31489 DISTANCE_SENSOR_DATA::ID => {
31490 DISTANCE_SENSOR_DATA::deser(version, payload).map(Self::DISTANCE_SENSOR)
31491 }
31492 SET_GPS_GLOBAL_ORIGIN_DATA::ID => {
31493 SET_GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::SET_GPS_GLOBAL_ORIGIN)
31494 }
31495 ISBD_LINK_STATUS_DATA::ID => {
31496 ISBD_LINK_STATUS_DATA::deser(version, payload).map(Self::ISBD_LINK_STATUS)
31497 }
31498 EVENT_DATA::ID => EVENT_DATA::deser(version, payload).map(Self::EVENT),
31499 GIMBAL_MANAGER_STATUS_DATA::ID => {
31500 GIMBAL_MANAGER_STATUS_DATA::deser(version, payload).map(Self::GIMBAL_MANAGER_STATUS)
31501 }
31502 PARAM_REQUEST_READ_DATA::ID => {
31503 PARAM_REQUEST_READ_DATA::deser(version, payload).map(Self::PARAM_REQUEST_READ)
31504 }
31505 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::deser(version, payload).map(Self::STATUSTEXT),
31506 CHANGE_OPERATOR_CONTROL_DATA::ID => {
31507 CHANGE_OPERATOR_CONTROL_DATA::deser(version, payload)
31508 .map(Self::CHANGE_OPERATOR_CONTROL)
31509 }
31510 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::deser(version, payload).map(Self::EFI_STATUS),
31511 LOG_REQUEST_END_DATA::ID => {
31512 LOG_REQUEST_END_DATA::deser(version, payload).map(Self::LOG_REQUEST_END)
31513 }
31514 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => {
31515 GIMBAL_MANAGER_SET_PITCHYAW_DATA::deser(version, payload)
31516 .map(Self::GIMBAL_MANAGER_SET_PITCHYAW)
31517 }
31518 UAVCAN_NODE_INFO_DATA::ID => {
31519 UAVCAN_NODE_INFO_DATA::deser(version, payload).map(Self::UAVCAN_NODE_INFO)
31520 }
31521 GPS_RTK_DATA::ID => GPS_RTK_DATA::deser(version, payload).map(Self::GPS_RTK),
31522 MISSION_REQUEST_INT_DATA::ID => {
31523 MISSION_REQUEST_INT_DATA::deser(version, payload).map(Self::MISSION_REQUEST_INT)
31524 }
31525 PING_DATA::ID => PING_DATA::deser(version, payload).map(Self::PING),
31526 DEBUG_FLOAT_ARRAY_DATA::ID => {
31527 DEBUG_FLOAT_ARRAY_DATA::deser(version, payload).map(Self::DEBUG_FLOAT_ARRAY)
31528 }
31529 SETUP_SIGNING_DATA::ID => {
31530 SETUP_SIGNING_DATA::deser(version, payload).map(Self::SETUP_SIGNING)
31531 }
31532 CAMERA_IMAGE_CAPTURED_DATA::ID => {
31533 CAMERA_IMAGE_CAPTURED_DATA::deser(version, payload).map(Self::CAMERA_IMAGE_CAPTURED)
31534 }
31535 BATTERY_STATUS_DATA::ID => {
31536 BATTERY_STATUS_DATA::deser(version, payload).map(Self::BATTERY_STATUS)
31537 }
31538 MISSION_COUNT_DATA::ID => {
31539 MISSION_COUNT_DATA::deser(version, payload).map(Self::MISSION_COUNT)
31540 }
31541 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => {
31542 OPEN_DRONE_ID_ARM_STATUS_DATA::deser(version, payload)
31543 .map(Self::OPEN_DRONE_ID_ARM_STATUS)
31544 }
31545 RC_CHANNELS_OVERRIDE_DATA::ID => {
31546 RC_CHANNELS_OVERRIDE_DATA::deser(version, payload).map(Self::RC_CHANNELS_OVERRIDE)
31547 }
31548 TERRAIN_REQUEST_DATA::ID => {
31549 TERRAIN_REQUEST_DATA::deser(version, payload).map(Self::TERRAIN_REQUEST)
31550 }
31551 OBSTACLE_DISTANCE_DATA::ID => {
31552 OBSTACLE_DISTANCE_DATA::deser(version, payload).map(Self::OBSTACLE_DISTANCE)
31553 }
31554 LANDING_TARGET_DATA::ID => {
31555 LANDING_TARGET_DATA::deser(version, payload).map(Self::LANDING_TARGET)
31556 }
31557 FOLLOW_TARGET_DATA::ID => {
31558 FOLLOW_TARGET_DATA::deser(version, payload).map(Self::FOLLOW_TARGET)
31559 }
31560 GLOBAL_POSITION_INT_COV_DATA::ID => {
31561 GLOBAL_POSITION_INT_COV_DATA::deser(version, payload)
31562 .map(Self::GLOBAL_POSITION_INT_COV)
31563 }
31564 CONTROL_SYSTEM_STATE_DATA::ID => {
31565 CONTROL_SYSTEM_STATE_DATA::deser(version, payload).map(Self::CONTROL_SYSTEM_STATE)
31566 }
31567 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::deser(version, payload).map(Self::GPS_INPUT),
31568 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::deser(version, payload).map(Self::PLAY_TUNE),
31569 HIL_OPTICAL_FLOW_DATA::ID => {
31570 HIL_OPTICAL_FLOW_DATA::deser(version, payload).map(Self::HIL_OPTICAL_FLOW)
31571 }
31572 VISION_SPEED_ESTIMATE_DATA::ID => {
31573 VISION_SPEED_ESTIMATE_DATA::deser(version, payload).map(Self::VISION_SPEED_ESTIMATE)
31574 }
31575 CAMERA_FOV_STATUS_DATA::ID => {
31576 CAMERA_FOV_STATUS_DATA::deser(version, payload).map(Self::CAMERA_FOV_STATUS)
31577 }
31578 MISSION_ITEM_REACHED_DATA::ID => {
31579 MISSION_ITEM_REACHED_DATA::deser(version, payload).map(Self::MISSION_ITEM_REACHED)
31580 }
31581 LOGGING_DATA_DATA::ID => {
31582 LOGGING_DATA_DATA::deser(version, payload).map(Self::LOGGING_DATA)
31583 }
31584 ONBOARD_COMPUTER_STATUS_DATA::ID => {
31585 ONBOARD_COMPUTER_STATUS_DATA::deser(version, payload)
31586 .map(Self::ONBOARD_COMPUTER_STATUS)
31587 }
31588 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::deser(version, payload).map(Self::LOG_ERASE),
31589 WHEEL_DISTANCE_DATA::ID => {
31590 WHEEL_DISTANCE_DATA::deser(version, payload).map(Self::WHEEL_DISTANCE)
31591 }
31592 PARAM_EXT_VALUE_DATA::ID => {
31593 PARAM_EXT_VALUE_DATA::deser(version, payload).map(Self::PARAM_EXT_VALUE)
31594 }
31595 RC_CHANNELS_SCALED_DATA::ID => {
31596 RC_CHANNELS_SCALED_DATA::deser(version, payload).map(Self::RC_CHANNELS_SCALED)
31597 }
31598 ATTITUDE_TARGET_DATA::ID => {
31599 ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::ATTITUDE_TARGET)
31600 }
31601 ATTITUDE_QUATERNION_DATA::ID => {
31602 ATTITUDE_QUATERNION_DATA::deser(version, payload).map(Self::ATTITUDE_QUATERNION)
31603 }
31604 HIL_STATE_DATA::ID => HIL_STATE_DATA::deser(version, payload).map(Self::HIL_STATE),
31605 AUTOPILOT_VERSION_DATA::ID => {
31606 AUTOPILOT_VERSION_DATA::deser(version, payload).map(Self::AUTOPILOT_VERSION)
31607 }
31608 UAVCAN_NODE_STATUS_DATA::ID => {
31609 UAVCAN_NODE_STATUS_DATA::deser(version, payload).map(Self::UAVCAN_NODE_STATUS)
31610 }
31611 HIL_ACTUATOR_CONTROLS_DATA::ID => {
31612 HIL_ACTUATOR_CONTROLS_DATA::deser(version, payload).map(Self::HIL_ACTUATOR_CONTROLS)
31613 }
31614 MISSION_ITEM_DATA::ID => {
31615 MISSION_ITEM_DATA::deser(version, payload).map(Self::MISSION_ITEM)
31616 }
31617 UTM_GLOBAL_POSITION_DATA::ID => {
31618 UTM_GLOBAL_POSITION_DATA::deser(version, payload).map(Self::UTM_GLOBAL_POSITION)
31619 }
31620 COMMAND_ACK_DATA::ID => {
31621 COMMAND_ACK_DATA::deser(version, payload).map(Self::COMMAND_ACK)
31622 }
31623 WIND_COV_DATA::ID => WIND_COV_DATA::deser(version, payload).map(Self::WIND_COV),
31624 DEBUG_DATA::ID => DEBUG_DATA::deser(version, payload).map(Self::DEBUG),
31625 LOGGING_ACK_DATA::ID => {
31626 LOGGING_ACK_DATA::deser(version, payload).map(Self::LOGGING_ACK)
31627 }
31628 AVAILABLE_MODES_DATA::ID => {
31629 AVAILABLE_MODES_DATA::deser(version, payload).map(Self::AVAILABLE_MODES)
31630 }
31631 STORAGE_INFORMATION_DATA::ID => {
31632 STORAGE_INFORMATION_DATA::deser(version, payload).map(Self::STORAGE_INFORMATION)
31633 }
31634 CAMERA_TRACKING_GEO_STATUS_DATA::ID => {
31635 CAMERA_TRACKING_GEO_STATUS_DATA::deser(version, payload)
31636 .map(Self::CAMERA_TRACKING_GEO_STATUS)
31637 }
31638 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => {
31639 OPEN_DRONE_ID_AUTHENTICATION_DATA::deser(version, payload)
31640 .map(Self::OPEN_DRONE_ID_AUTHENTICATION)
31641 }
31642 ODOMETRY_DATA::ID => ODOMETRY_DATA::deser(version, payload).map(Self::ODOMETRY),
31643 SYSTEM_TIME_DATA::ID => {
31644 SYSTEM_TIME_DATA::deser(version, payload).map(Self::SYSTEM_TIME)
31645 }
31646 VICON_POSITION_ESTIMATE_DATA::ID => {
31647 VICON_POSITION_ESTIMATE_DATA::deser(version, payload)
31648 .map(Self::VICON_POSITION_ESTIMATE)
31649 }
31650 CAN_FILTER_MODIFY_DATA::ID => {
31651 CAN_FILTER_MODIFY_DATA::deser(version, payload).map(Self::CAN_FILTER_MODIFY)
31652 }
31653 OPTICAL_FLOW_RAD_DATA::ID => {
31654 OPTICAL_FLOW_RAD_DATA::deser(version, payload).map(Self::OPTICAL_FLOW_RAD)
31655 }
31656 SMART_BATTERY_INFO_DATA::ID => {
31657 SMART_BATTERY_INFO_DATA::deser(version, payload).map(Self::SMART_BATTERY_INFO)
31658 }
31659 PARAM_REQUEST_LIST_DATA::ID => {
31660 PARAM_REQUEST_LIST_DATA::deser(version, payload).map(Self::PARAM_REQUEST_LIST)
31661 }
31662 LINK_NODE_STATUS_DATA::ID => {
31663 LINK_NODE_STATUS_DATA::deser(version, payload).map(Self::LINK_NODE_STATUS)
31664 }
31665 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => {
31666 OPEN_DRONE_ID_OPERATOR_ID_DATA::deser(version, payload)
31667 .map(Self::OPEN_DRONE_ID_OPERATOR_ID)
31668 }
31669 NAMED_VALUE_INT_DATA::ID => {
31670 NAMED_VALUE_INT_DATA::deser(version, payload).map(Self::NAMED_VALUE_INT)
31671 }
31672 BATTERY_INFO_DATA::ID => {
31673 BATTERY_INFO_DATA::deser(version, payload).map(Self::BATTERY_INFO)
31674 }
31675 GPS_GLOBAL_ORIGIN_DATA::ID => {
31676 GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::GPS_GLOBAL_ORIGIN)
31677 }
31678 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
31679 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::deser(version, payload)
31680 .map(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET)
31681 }
31682 HIL_STATE_QUATERNION_DATA::ID => {
31683 HIL_STATE_QUATERNION_DATA::deser(version, payload).map(Self::HIL_STATE_QUATERNION)
31684 }
31685 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::deser(version, payload).map(Self::DEBUG_VECT),
31686 VIDEO_STREAM_STATUS_DATA::ID => {
31687 VIDEO_STREAM_STATUS_DATA::deser(version, payload).map(Self::VIDEO_STREAM_STATUS)
31688 }
31689 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
31690 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::deser(version, payload)
31691 .map(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL)
31692 }
31693 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => {
31694 SET_POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
31695 .map(Self::SET_POSITION_TARGET_LOCAL_NED)
31696 }
31697 PARAM_EXT_ACK_DATA::ID => {
31698 PARAM_EXT_ACK_DATA::deser(version, payload).map(Self::PARAM_EXT_ACK)
31699 }
31700 SAFETY_SET_ALLOWED_AREA_DATA::ID => {
31701 SAFETY_SET_ALLOWED_AREA_DATA::deser(version, payload)
31702 .map(Self::SAFETY_SET_ALLOWED_AREA)
31703 }
31704 COMMAND_LONG_DATA::ID => {
31705 COMMAND_LONG_DATA::deser(version, payload).map(Self::COMMAND_LONG)
31706 }
31707 MOUNT_ORIENTATION_DATA::ID => {
31708 MOUNT_ORIENTATION_DATA::deser(version, payload).map(Self::MOUNT_ORIENTATION)
31709 }
31710 POWER_STATUS_DATA::ID => {
31711 POWER_STATUS_DATA::deser(version, payload).map(Self::POWER_STATUS)
31712 }
31713 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => {
31714 CHANGE_OPERATOR_CONTROL_ACK_DATA::deser(version, payload)
31715 .map(Self::CHANGE_OPERATOR_CONTROL_ACK)
31716 }
31717 GPS_RAW_INT_DATA::ID => {
31718 GPS_RAW_INT_DATA::deser(version, payload).map(Self::GPS_RAW_INT)
31719 }
31720 SIM_STATE_DATA::ID => SIM_STATE_DATA::deser(version, payload).map(Self::SIM_STATE),
31721 CELLULAR_CONFIG_DATA::ID => {
31722 CELLULAR_CONFIG_DATA::deser(version, payload).map(Self::CELLULAR_CONFIG)
31723 }
31724 LOCAL_POSITION_NED_DATA::ID => {
31725 LOCAL_POSITION_NED_DATA::deser(version, payload).map(Self::LOCAL_POSITION_NED)
31726 }
31727 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => {
31728 CAMERA_TRACKING_IMAGE_STATUS_DATA::deser(version, payload)
31729 .map(Self::CAMERA_TRACKING_IMAGE_STATUS)
31730 }
31731 TUNNEL_DATA::ID => TUNNEL_DATA::deser(version, payload).map(Self::TUNNEL),
31732 RC_CHANNELS_DATA::ID => {
31733 RC_CHANNELS_DATA::deser(version, payload).map(Self::RC_CHANNELS)
31734 }
31735 NAMED_VALUE_FLOAT_DATA::ID => {
31736 NAMED_VALUE_FLOAT_DATA::deser(version, payload).map(Self::NAMED_VALUE_FLOAT)
31737 }
31738 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => {
31739 SET_ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
31740 .map(Self::SET_ACTUATOR_CONTROL_TARGET)
31741 }
31742 POSITION_TARGET_LOCAL_NED_DATA::ID => {
31743 POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
31744 .map(Self::POSITION_TARGET_LOCAL_NED)
31745 }
31746 MEMORY_VECT_DATA::ID => {
31747 MEMORY_VECT_DATA::deser(version, payload).map(Self::MEMORY_VECT)
31748 }
31749 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::deser(version, payload)
31750 .map(Self::PARAM_EXT_REQUEST_LIST),
31751 POSITION_TARGET_GLOBAL_INT_DATA::ID => {
31752 POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
31753 .map(Self::POSITION_TARGET_GLOBAL_INT)
31754 }
31755 BUTTON_CHANGE_DATA::ID => {
31756 BUTTON_CHANGE_DATA::deser(version, payload).map(Self::BUTTON_CHANGE)
31757 }
31758 LOGGING_DATA_ACKED_DATA::ID => {
31759 LOGGING_DATA_ACKED_DATA::deser(version, payload).map(Self::LOGGING_DATA_ACKED)
31760 }
31761 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::deser(version, payload).map(Self::LOG_ENTRY),
31762 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => {
31763 GIMBAL_DEVICE_SET_ATTITUDE_DATA::deser(version, payload)
31764 .map(Self::GIMBAL_DEVICE_SET_ATTITUDE)
31765 }
31766 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::deser(version, payload).map(Self::AIS_VESSEL),
31767 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
31768 TRAJECTORY_REPRESENTATION_BEZIER_DATA::deser(version, payload)
31769 .map(Self::TRAJECTORY_REPRESENTATION_BEZIER)
31770 }
31771 MAG_CAL_REPORT_DATA::ID => {
31772 MAG_CAL_REPORT_DATA::deser(version, payload).map(Self::MAG_CAL_REPORT)
31773 }
31774 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::deser(version, payload).map(Self::GPS2_RAW),
31775 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::deser(version, payload).map(Self::HEARTBEAT),
31776 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::deser(version, payload).map(Self::SYS_STATUS),
31777 VIDEO_STREAM_INFORMATION_DATA::ID => {
31778 VIDEO_STREAM_INFORMATION_DATA::deser(version, payload)
31779 .map(Self::VIDEO_STREAM_INFORMATION)
31780 }
31781 VIBRATION_DATA::ID => VIBRATION_DATA::deser(version, payload).map(Self::VIBRATION),
31782 WIFI_CONFIG_AP_DATA::ID => {
31783 WIFI_CONFIG_AP_DATA::deser(version, payload).map(Self::WIFI_CONFIG_AP)
31784 }
31785 MISSION_REQUEST_LIST_DATA::ID => {
31786 MISSION_REQUEST_LIST_DATA::deser(version, payload).map(Self::MISSION_REQUEST_LIST)
31787 }
31788 RAW_RPM_DATA::ID => RAW_RPM_DATA::deser(version, payload).map(Self::RAW_RPM),
31789 PLAY_TUNE_V2_DATA::ID => {
31790 PLAY_TUNE_V2_DATA::deser(version, payload).map(Self::PLAY_TUNE_V2)
31791 }
31792 SUPPORTED_TUNES_DATA::ID => {
31793 SUPPORTED_TUNES_DATA::deser(version, payload).map(Self::SUPPORTED_TUNES)
31794 }
31795 REQUEST_EVENT_DATA::ID => {
31796 REQUEST_EVENT_DATA::deser(version, payload).map(Self::REQUEST_EVENT)
31797 }
31798 SCALED_PRESSURE_DATA::ID => {
31799 SCALED_PRESSURE_DATA::deser(version, payload).map(Self::SCALED_PRESSURE)
31800 }
31801 SCALED_PRESSURE3_DATA::ID => {
31802 SCALED_PRESSURE3_DATA::deser(version, payload).map(Self::SCALED_PRESSURE3)
31803 }
31804 GIMBAL_DEVICE_INFORMATION_DATA::ID => {
31805 GIMBAL_DEVICE_INFORMATION_DATA::deser(version, payload)
31806 .map(Self::GIMBAL_DEVICE_INFORMATION)
31807 }
31808 MISSION_WRITE_PARTIAL_LIST_DATA::ID => {
31809 MISSION_WRITE_PARTIAL_LIST_DATA::deser(version, payload)
31810 .map(Self::MISSION_WRITE_PARTIAL_LIST)
31811 }
31812 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => {
31813 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::deser(version, payload)
31814 .map(Self::OPEN_DRONE_ID_SYSTEM_UPDATE)
31815 }
31816 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::deser(version, payload)
31817 .map(Self::CURRENT_EVENT_SEQUENCE),
31818 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
31819 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::deser(version, payload)
31820 .map(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS)
31821 }
31822 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
31823 SET_POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
31824 .map(Self::SET_POSITION_TARGET_GLOBAL_INT)
31825 }
31826 _ => Err(::mavlink_core::error::ParserError::UnknownMessage { id }),
31827 }
31828 }
31829 fn message_name(&self) -> &'static str {
31830 match self {
31831 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::NAME,
31832 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::NAME,
31833 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME,
31834 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::NAME,
31835 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::NAME,
31836 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::NAME,
31837 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME,
31838 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::NAME,
31839 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::NAME,
31840 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::NAME,
31841 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::NAME,
31842 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::NAME,
31843 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::NAME,
31844 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::NAME,
31845 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::NAME,
31846 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::NAME,
31847 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME,
31848 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::NAME,
31849 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::NAME,
31850 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::NAME,
31851 Self::COLLISION(..) => COLLISION_DATA::NAME,
31852 Self::GPS2_RTK(..) => GPS2_RTK_DATA::NAME,
31853 Self::COMMAND_INT(..) => COMMAND_INT_DATA::NAME,
31854 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::NAME,
31855 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::NAME,
31856 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::NAME,
31857 Self::SET_MODE(..) => SET_MODE_DATA::NAME,
31858 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::NAME,
31859 Self::TIMESYNC(..) => TIMESYNC_DATA::NAME,
31860 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::NAME,
31861 Self::HIL_GPS(..) => HIL_GPS_DATA::NAME,
31862 Self::CAN_FRAME(..) => CAN_FRAME_DATA::NAME,
31863 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::NAME,
31864 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::NAME,
31865 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::NAME,
31866 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::NAME,
31867 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::NAME,
31868 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::NAME,
31869 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::NAME,
31870 Self::VFR_HUD(..) => VFR_HUD_DATA::NAME,
31871 Self::ALTITUDE(..) => ALTITUDE_DATA::NAME,
31872 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::NAME,
31873 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::NAME,
31874 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::NAME,
31875 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::NAME,
31876 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
31877 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME
31878 }
31879 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::NAME,
31880 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::NAME,
31881 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::NAME,
31882 Self::GPS_STATUS(..) => GPS_STATUS_DATA::NAME,
31883 Self::ATTITUDE(..) => ATTITUDE_DATA::NAME,
31884 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::NAME,
31885 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::NAME,
31886 Self::ESC_STATUS(..) => ESC_STATUS_DATA::NAME,
31887 Self::RAW_IMU(..) => RAW_IMU_DATA::NAME,
31888 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::NAME,
31889 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::NAME,
31890 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::NAME,
31891 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::NAME,
31892 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::NAME,
31893 Self::SCALED_IMU(..) => SCALED_IMU_DATA::NAME,
31894 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::NAME,
31895 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::NAME,
31896 Self::DATA_STREAM(..) => DATA_STREAM_DATA::NAME,
31897 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::NAME,
31898 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::NAME,
31899 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::NAME,
31900 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::NAME,
31901 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::NAME,
31902 Self::HOME_POSITION(..) => HOME_POSITION_DATA::NAME,
31903 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::NAME,
31904 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::NAME,
31905 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::NAME,
31906 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::NAME,
31907 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::NAME,
31908 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::NAME,
31909 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::NAME,
31910 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::NAME,
31911 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME,
31912 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::NAME,
31913 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::NAME,
31914 Self::PARAM_SET(..) => PARAM_SET_DATA::NAME,
31915 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::NAME,
31916 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::NAME,
31917 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::NAME,
31918 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::NAME,
31919 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::NAME,
31920 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::NAME,
31921 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::NAME,
31922 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::NAME,
31923 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::NAME,
31924 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::NAME,
31925 Self::MISSION_ACK(..) => MISSION_ACK_DATA::NAME,
31926 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::NAME,
31927 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::NAME,
31928 Self::AUTH_KEY(..) => AUTH_KEY_DATA::NAME,
31929 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::NAME,
31930 Self::LOG_DATA(..) => LOG_DATA_DATA::NAME,
31931 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::NAME,
31932 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::NAME,
31933 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::NAME,
31934 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::NAME,
31935 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::NAME,
31936 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::NAME,
31937 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::NAME,
31938 Self::ESC_INFO(..) => ESC_INFO_DATA::NAME,
31939 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::NAME,
31940 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::NAME,
31941 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::NAME,
31942 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::NAME,
31943 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::NAME,
31944 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::NAME,
31945 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::NAME,
31946 Self::EVENT(..) => EVENT_DATA::NAME,
31947 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::NAME,
31948 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::NAME,
31949 Self::STATUSTEXT(..) => STATUSTEXT_DATA::NAME,
31950 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::NAME,
31951 Self::EFI_STATUS(..) => EFI_STATUS_DATA::NAME,
31952 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::NAME,
31953 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME,
31954 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::NAME,
31955 Self::GPS_RTK(..) => GPS_RTK_DATA::NAME,
31956 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::NAME,
31957 Self::PING(..) => PING_DATA::NAME,
31958 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::NAME,
31959 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::NAME,
31960 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::NAME,
31961 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::NAME,
31962 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::NAME,
31963 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::NAME,
31964 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::NAME,
31965 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::NAME,
31966 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::NAME,
31967 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::NAME,
31968 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::NAME,
31969 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::NAME,
31970 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::NAME,
31971 Self::GPS_INPUT(..) => GPS_INPUT_DATA::NAME,
31972 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::NAME,
31973 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::NAME,
31974 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::NAME,
31975 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::NAME,
31976 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::NAME,
31977 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::NAME,
31978 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::NAME,
31979 Self::LOG_ERASE(..) => LOG_ERASE_DATA::NAME,
31980 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::NAME,
31981 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::NAME,
31982 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::NAME,
31983 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::NAME,
31984 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::NAME,
31985 Self::HIL_STATE(..) => HIL_STATE_DATA::NAME,
31986 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::NAME,
31987 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::NAME,
31988 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::NAME,
31989 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::NAME,
31990 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::NAME,
31991 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::NAME,
31992 Self::WIND_COV(..) => WIND_COV_DATA::NAME,
31993 Self::DEBUG(..) => DEBUG_DATA::NAME,
31994 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::NAME,
31995 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::NAME,
31996 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::NAME,
31997 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::NAME,
31998 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME,
31999 Self::ODOMETRY(..) => ODOMETRY_DATA::NAME,
32000 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::NAME,
32001 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::NAME,
32002 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::NAME,
32003 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::NAME,
32004 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::NAME,
32005 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::NAME,
32006 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::NAME,
32007 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME,
32008 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::NAME,
32009 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::NAME,
32010 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::NAME,
32011 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
32012 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME
32013 }
32014 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::NAME,
32015 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::NAME,
32016 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::NAME,
32017 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
32018 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME
32019 }
32020 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::NAME,
32021 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::NAME,
32022 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::NAME,
32023 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::NAME,
32024 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::NAME,
32025 Self::POWER_STATUS(..) => POWER_STATUS_DATA::NAME,
32026 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME,
32027 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::NAME,
32028 Self::SIM_STATE(..) => SIM_STATE_DATA::NAME,
32029 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::NAME,
32030 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::NAME,
32031 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME,
32032 Self::TUNNEL(..) => TUNNEL_DATA::NAME,
32033 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::NAME,
32034 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::NAME,
32035 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::NAME,
32036 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::NAME,
32037 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::NAME,
32038 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::NAME,
32039 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::NAME,
32040 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::NAME,
32041 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::NAME,
32042 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::NAME,
32043 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME,
32044 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::NAME,
32045 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => {
32046 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME
32047 }
32048 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::NAME,
32049 Self::GPS2_RAW(..) => GPS2_RAW_DATA::NAME,
32050 Self::HEARTBEAT(..) => HEARTBEAT_DATA::NAME,
32051 Self::SYS_STATUS(..) => SYS_STATUS_DATA::NAME,
32052 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::NAME,
32053 Self::VIBRATION(..) => VIBRATION_DATA::NAME,
32054 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::NAME,
32055 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::NAME,
32056 Self::RAW_RPM(..) => RAW_RPM_DATA::NAME,
32057 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::NAME,
32058 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::NAME,
32059 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::NAME,
32060 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::NAME,
32061 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::NAME,
32062 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::NAME,
32063 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::NAME,
32064 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME,
32065 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::NAME,
32066 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
32067 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME
32068 }
32069 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME,
32070 }
32071 }
32072 fn message_id(&self) -> u32 {
32073 match self {
32074 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::ID,
32075 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::ID,
32076 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID,
32077 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::ID,
32078 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::ID,
32079 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::ID,
32080 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID,
32081 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::ID,
32082 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::ID,
32083 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::ID,
32084 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::ID,
32085 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::ID,
32086 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::ID,
32087 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::ID,
32088 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::ID,
32089 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::ID,
32090 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID,
32091 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::ID,
32092 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::ID,
32093 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::ID,
32094 Self::COLLISION(..) => COLLISION_DATA::ID,
32095 Self::GPS2_RTK(..) => GPS2_RTK_DATA::ID,
32096 Self::COMMAND_INT(..) => COMMAND_INT_DATA::ID,
32097 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::ID,
32098 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::ID,
32099 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::ID,
32100 Self::SET_MODE(..) => SET_MODE_DATA::ID,
32101 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::ID,
32102 Self::TIMESYNC(..) => TIMESYNC_DATA::ID,
32103 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::ID,
32104 Self::HIL_GPS(..) => HIL_GPS_DATA::ID,
32105 Self::CAN_FRAME(..) => CAN_FRAME_DATA::ID,
32106 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::ID,
32107 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::ID,
32108 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::ID,
32109 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::ID,
32110 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::ID,
32111 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::ID,
32112 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::ID,
32113 Self::VFR_HUD(..) => VFR_HUD_DATA::ID,
32114 Self::ALTITUDE(..) => ALTITUDE_DATA::ID,
32115 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::ID,
32116 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::ID,
32117 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::ID,
32118 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::ID,
32119 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
32120 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID
32121 }
32122 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::ID,
32123 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::ID,
32124 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::ID,
32125 Self::GPS_STATUS(..) => GPS_STATUS_DATA::ID,
32126 Self::ATTITUDE(..) => ATTITUDE_DATA::ID,
32127 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::ID,
32128 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::ID,
32129 Self::ESC_STATUS(..) => ESC_STATUS_DATA::ID,
32130 Self::RAW_IMU(..) => RAW_IMU_DATA::ID,
32131 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::ID,
32132 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::ID,
32133 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::ID,
32134 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::ID,
32135 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::ID,
32136 Self::SCALED_IMU(..) => SCALED_IMU_DATA::ID,
32137 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::ID,
32138 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::ID,
32139 Self::DATA_STREAM(..) => DATA_STREAM_DATA::ID,
32140 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::ID,
32141 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::ID,
32142 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::ID,
32143 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::ID,
32144 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::ID,
32145 Self::HOME_POSITION(..) => HOME_POSITION_DATA::ID,
32146 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::ID,
32147 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::ID,
32148 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::ID,
32149 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::ID,
32150 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::ID,
32151 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::ID,
32152 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::ID,
32153 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::ID,
32154 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID,
32155 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::ID,
32156 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::ID,
32157 Self::PARAM_SET(..) => PARAM_SET_DATA::ID,
32158 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::ID,
32159 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::ID,
32160 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::ID,
32161 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::ID,
32162 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::ID,
32163 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::ID,
32164 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::ID,
32165 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::ID,
32166 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::ID,
32167 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::ID,
32168 Self::MISSION_ACK(..) => MISSION_ACK_DATA::ID,
32169 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::ID,
32170 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::ID,
32171 Self::AUTH_KEY(..) => AUTH_KEY_DATA::ID,
32172 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::ID,
32173 Self::LOG_DATA(..) => LOG_DATA_DATA::ID,
32174 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::ID,
32175 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::ID,
32176 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::ID,
32177 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::ID,
32178 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::ID,
32179 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::ID,
32180 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::ID,
32181 Self::ESC_INFO(..) => ESC_INFO_DATA::ID,
32182 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::ID,
32183 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::ID,
32184 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::ID,
32185 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::ID,
32186 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::ID,
32187 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::ID,
32188 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::ID,
32189 Self::EVENT(..) => EVENT_DATA::ID,
32190 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::ID,
32191 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::ID,
32192 Self::STATUSTEXT(..) => STATUSTEXT_DATA::ID,
32193 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::ID,
32194 Self::EFI_STATUS(..) => EFI_STATUS_DATA::ID,
32195 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::ID,
32196 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID,
32197 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::ID,
32198 Self::GPS_RTK(..) => GPS_RTK_DATA::ID,
32199 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::ID,
32200 Self::PING(..) => PING_DATA::ID,
32201 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::ID,
32202 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::ID,
32203 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::ID,
32204 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::ID,
32205 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::ID,
32206 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::ID,
32207 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::ID,
32208 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::ID,
32209 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::ID,
32210 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::ID,
32211 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::ID,
32212 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::ID,
32213 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::ID,
32214 Self::GPS_INPUT(..) => GPS_INPUT_DATA::ID,
32215 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::ID,
32216 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::ID,
32217 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::ID,
32218 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::ID,
32219 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::ID,
32220 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::ID,
32221 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::ID,
32222 Self::LOG_ERASE(..) => LOG_ERASE_DATA::ID,
32223 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::ID,
32224 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::ID,
32225 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::ID,
32226 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::ID,
32227 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::ID,
32228 Self::HIL_STATE(..) => HIL_STATE_DATA::ID,
32229 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::ID,
32230 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::ID,
32231 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::ID,
32232 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::ID,
32233 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::ID,
32234 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::ID,
32235 Self::WIND_COV(..) => WIND_COV_DATA::ID,
32236 Self::DEBUG(..) => DEBUG_DATA::ID,
32237 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::ID,
32238 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::ID,
32239 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::ID,
32240 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::ID,
32241 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::ID,
32242 Self::ODOMETRY(..) => ODOMETRY_DATA::ID,
32243 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::ID,
32244 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::ID,
32245 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::ID,
32246 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::ID,
32247 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::ID,
32248 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::ID,
32249 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::ID,
32250 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::ID,
32251 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::ID,
32252 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::ID,
32253 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::ID,
32254 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
32255 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID
32256 }
32257 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::ID,
32258 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::ID,
32259 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::ID,
32260 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
32261 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID
32262 }
32263 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::ID,
32264 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::ID,
32265 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::ID,
32266 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::ID,
32267 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::ID,
32268 Self::POWER_STATUS(..) => POWER_STATUS_DATA::ID,
32269 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::ID,
32270 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::ID,
32271 Self::SIM_STATE(..) => SIM_STATE_DATA::ID,
32272 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::ID,
32273 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::ID,
32274 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::ID,
32275 Self::TUNNEL(..) => TUNNEL_DATA::ID,
32276 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::ID,
32277 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::ID,
32278 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::ID,
32279 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::ID,
32280 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::ID,
32281 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::ID,
32282 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::ID,
32283 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::ID,
32284 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::ID,
32285 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::ID,
32286 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID,
32287 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::ID,
32288 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID,
32289 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::ID,
32290 Self::GPS2_RAW(..) => GPS2_RAW_DATA::ID,
32291 Self::HEARTBEAT(..) => HEARTBEAT_DATA::ID,
32292 Self::SYS_STATUS(..) => SYS_STATUS_DATA::ID,
32293 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::ID,
32294 Self::VIBRATION(..) => VIBRATION_DATA::ID,
32295 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::ID,
32296 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::ID,
32297 Self::RAW_RPM(..) => RAW_RPM_DATA::ID,
32298 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::ID,
32299 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::ID,
32300 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::ID,
32301 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::ID,
32302 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::ID,
32303 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::ID,
32304 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::ID,
32305 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID,
32306 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::ID,
32307 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
32308 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID
32309 }
32310 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::ID,
32311 }
32312 }
32313 fn message_id_from_name(name: &str) -> Option<u32> {
32314 match name {
32315 MANUAL_CONTROL_DATA::NAME => Some(MANUAL_CONTROL_DATA::ID),
32316 V2_EXTENSION_DATA::NAME => Some(V2_EXTENSION_DATA::ID),
32317 GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME => {
32318 Some(GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID)
32319 }
32320 OPTICAL_FLOW_DATA::NAME => Some(OPTICAL_FLOW_DATA::ID),
32321 TIME_ESTIMATE_TO_TARGET_DATA::NAME => Some(TIME_ESTIMATE_TO_TARGET_DATA::ID),
32322 HIL_RC_INPUTS_RAW_DATA::NAME => Some(HIL_RC_INPUTS_RAW_DATA::ID),
32323 OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME => Some(OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID),
32324 ATTITUDE_QUATERNION_COV_DATA::NAME => Some(ATTITUDE_QUATERNION_COV_DATA::ID),
32325 GENERATOR_STATUS_DATA::NAME => Some(GENERATOR_STATUS_DATA::ID),
32326 FILE_TRANSFER_PROTOCOL_DATA::NAME => Some(FILE_TRANSFER_PROTOCOL_DATA::ID),
32327 ACTUATOR_OUTPUT_STATUS_DATA::NAME => Some(ACTUATOR_OUTPUT_STATUS_DATA::ID),
32328 COMPONENT_INFORMATION_BASIC_DATA::NAME => Some(COMPONENT_INFORMATION_BASIC_DATA::ID),
32329 FUEL_STATUS_DATA::NAME => Some(FUEL_STATUS_DATA::ID),
32330 OPEN_DRONE_ID_BASIC_ID_DATA::NAME => Some(OPEN_DRONE_ID_BASIC_ID_DATA::ID),
32331 ESTIMATOR_STATUS_DATA::NAME => Some(ESTIMATOR_STATUS_DATA::ID),
32332 MISSION_CURRENT_DATA::NAME => Some(MISSION_CURRENT_DATA::ID),
32333 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME => {
32334 Some(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID)
32335 }
32336 GLOBAL_POSITION_INT_DATA::NAME => Some(GLOBAL_POSITION_INT_DATA::ID),
32337 SET_ATTITUDE_TARGET_DATA::NAME => Some(SET_ATTITUDE_TARGET_DATA::ID),
32338 PARAM_EXT_REQUEST_READ_DATA::NAME => Some(PARAM_EXT_REQUEST_READ_DATA::ID),
32339 COLLISION_DATA::NAME => Some(COLLISION_DATA::ID),
32340 GPS2_RTK_DATA::NAME => Some(GPS2_RTK_DATA::ID),
32341 COMMAND_INT_DATA::NAME => Some(COMMAND_INT_DATA::ID),
32342 OPEN_DRONE_ID_SELF_ID_DATA::NAME => Some(OPEN_DRONE_ID_SELF_ID_DATA::ID),
32343 LOCAL_POSITION_NED_COV_DATA::NAME => Some(LOCAL_POSITION_NED_COV_DATA::ID),
32344 HIL_SENSOR_DATA::NAME => Some(HIL_SENSOR_DATA::ID),
32345 SET_MODE_DATA::NAME => Some(SET_MODE_DATA::ID),
32346 RAW_PRESSURE_DATA::NAME => Some(RAW_PRESSURE_DATA::ID),
32347 TIMESYNC_DATA::NAME => Some(TIMESYNC_DATA::ID),
32348 REQUEST_DATA_STREAM_DATA::NAME => Some(REQUEST_DATA_STREAM_DATA::ID),
32349 HIL_GPS_DATA::NAME => Some(HIL_GPS_DATA::ID),
32350 CAN_FRAME_DATA::NAME => Some(CAN_FRAME_DATA::ID),
32351 HYGROMETER_SENSOR_DATA::NAME => Some(HYGROMETER_SENSOR_DATA::ID),
32352 COMPONENT_INFORMATION_DATA::NAME => Some(COMPONENT_INFORMATION_DATA::ID),
32353 TERRAIN_REPORT_DATA::NAME => Some(TERRAIN_REPORT_DATA::ID),
32354 SCALED_PRESSURE2_DATA::NAME => Some(SCALED_PRESSURE2_DATA::ID),
32355 CAMERA_INFORMATION_DATA::NAME => Some(CAMERA_INFORMATION_DATA::ID),
32356 HIGH_LATENCY2_DATA::NAME => Some(HIGH_LATENCY2_DATA::ID),
32357 ADSB_VEHICLE_DATA::NAME => Some(ADSB_VEHICLE_DATA::ID),
32358 VFR_HUD_DATA::NAME => Some(VFR_HUD_DATA::ID),
32359 ALTITUDE_DATA::NAME => Some(ALTITUDE_DATA::ID),
32360 MISSION_REQUEST_DATA::NAME => Some(MISSION_REQUEST_DATA::ID),
32361 CANFD_FRAME_DATA::NAME => Some(CANFD_FRAME_DATA::ID),
32362 NAV_CONTROLLER_OUTPUT_DATA::NAME => Some(NAV_CONTROLLER_OUTPUT_DATA::ID),
32363 HIL_CONTROLS_DATA::NAME => Some(HIL_CONTROLS_DATA::ID),
32364 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME => {
32365 Some(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID)
32366 }
32367 VISION_POSITION_ESTIMATE_DATA::NAME => Some(VISION_POSITION_ESTIMATE_DATA::ID),
32368 COMMAND_CANCEL_DATA::NAME => Some(COMMAND_CANCEL_DATA::ID),
32369 CAMERA_SETTINGS_DATA::NAME => Some(CAMERA_SETTINGS_DATA::ID),
32370 GPS_STATUS_DATA::NAME => Some(GPS_STATUS_DATA::ID),
32371 ATTITUDE_DATA::NAME => Some(ATTITUDE_DATA::ID),
32372 ENCAPSULATED_DATA_DATA::NAME => Some(ENCAPSULATED_DATA_DATA::ID),
32373 CELLULAR_STATUS_DATA::NAME => Some(CELLULAR_STATUS_DATA::ID),
32374 ESC_STATUS_DATA::NAME => Some(ESC_STATUS_DATA::ID),
32375 RAW_IMU_DATA::NAME => Some(RAW_IMU_DATA::ID),
32376 HIGH_LATENCY_DATA::NAME => Some(HIGH_LATENCY_DATA::ID),
32377 AVAILABLE_MODES_MONITOR_DATA::NAME => Some(AVAILABLE_MODES_MONITOR_DATA::ID),
32378 ILLUMINATOR_STATUS_DATA::NAME => Some(ILLUMINATOR_STATUS_DATA::ID),
32379 MISSION_ITEM_INT_DATA::NAME => Some(MISSION_ITEM_INT_DATA::ID),
32380 CURRENT_MODE_DATA::NAME => Some(CURRENT_MODE_DATA::ID),
32381 SCALED_IMU_DATA::NAME => Some(SCALED_IMU_DATA::ID),
32382 SAFETY_ALLOWED_AREA_DATA::NAME => Some(SAFETY_ALLOWED_AREA_DATA::ID),
32383 TERRAIN_CHECK_DATA::NAME => Some(TERRAIN_CHECK_DATA::ID),
32384 DATA_STREAM_DATA::NAME => Some(DATA_STREAM_DATA::ID),
32385 LOG_REQUEST_LIST_DATA::NAME => Some(LOG_REQUEST_LIST_DATA::ID),
32386 EXTENDED_SYS_STATE_DATA::NAME => Some(EXTENDED_SYS_STATE_DATA::ID),
32387 CAMERA_TRIGGER_DATA::NAME => Some(CAMERA_TRIGGER_DATA::ID),
32388 MESSAGE_INTERVAL_DATA::NAME => Some(MESSAGE_INTERVAL_DATA::ID),
32389 GPS_INJECT_DATA_DATA::NAME => Some(GPS_INJECT_DATA_DATA::ID),
32390 HOME_POSITION_DATA::NAME => Some(HOME_POSITION_DATA::ID),
32391 PARAM_MAP_RC_DATA::NAME => Some(PARAM_MAP_RC_DATA::ID),
32392 SERIAL_CONTROL_DATA::NAME => Some(SERIAL_CONTROL_DATA::ID),
32393 OPEN_DRONE_ID_LOCATION_DATA::NAME => Some(OPEN_DRONE_ID_LOCATION_DATA::ID),
32394 MISSION_SET_CURRENT_DATA::NAME => Some(MISSION_SET_CURRENT_DATA::ID),
32395 MANUAL_SETPOINT_DATA::NAME => Some(MANUAL_SETPOINT_DATA::ID),
32396 FENCE_STATUS_DATA::NAME => Some(FENCE_STATUS_DATA::ID),
32397 FLIGHT_INFORMATION_DATA::NAME => Some(FLIGHT_INFORMATION_DATA::ID),
32398 GIMBAL_MANAGER_INFORMATION_DATA::NAME => Some(GIMBAL_MANAGER_INFORMATION_DATA::ID),
32399 GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID),
32400 RESOURCE_REQUEST_DATA::NAME => Some(RESOURCE_REQUEST_DATA::ID),
32401 MISSION_CLEAR_ALL_DATA::NAME => Some(MISSION_CLEAR_ALL_DATA::ID),
32402 PARAM_SET_DATA::NAME => Some(PARAM_SET_DATA::ID),
32403 LOG_REQUEST_DATA_DATA::NAME => Some(LOG_REQUEST_DATA_DATA::ID),
32404 CAMERA_THERMAL_RANGE_DATA::NAME => Some(CAMERA_THERMAL_RANGE_DATA::ID),
32405 RESPONSE_EVENT_ERROR_DATA::NAME => Some(RESPONSE_EVENT_ERROR_DATA::ID),
32406 SCALED_IMU3_DATA::NAME => Some(SCALED_IMU3_DATA::ID),
32407 CAMERA_CAPTURE_STATUS_DATA::NAME => Some(CAMERA_CAPTURE_STATUS_DATA::ID),
32408 PARAM_EXT_SET_DATA::NAME => Some(PARAM_EXT_SET_DATA::ID),
32409 ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(ACTUATOR_CONTROL_TARGET_DATA::ID),
32410 ORBIT_EXECUTION_STATUS_DATA::NAME => Some(ORBIT_EXECUTION_STATUS_DATA::ID),
32411 HIGHRES_IMU_DATA::NAME => Some(HIGHRES_IMU_DATA::ID),
32412 OPEN_DRONE_ID_SYSTEM_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_DATA::ID),
32413 MISSION_ACK_DATA::NAME => Some(MISSION_ACK_DATA::ID),
32414 GPS_RTCM_DATA_DATA::NAME => Some(GPS_RTCM_DATA_DATA::ID),
32415 RADIO_STATUS_DATA::NAME => Some(RADIO_STATUS_DATA::ID),
32416 AUTH_KEY_DATA::NAME => Some(AUTH_KEY_DATA::ID),
32417 RC_CHANNELS_RAW_DATA::NAME => Some(RC_CHANNELS_RAW_DATA::ID),
32418 LOG_DATA_DATA::NAME => Some(LOG_DATA_DATA::ID),
32419 PARAM_VALUE_DATA::NAME => Some(PARAM_VALUE_DATA::ID),
32420 ATT_POS_MOCAP_DATA::NAME => Some(ATT_POS_MOCAP_DATA::ID),
32421 SET_HOME_POSITION_DATA::NAME => Some(SET_HOME_POSITION_DATA::ID),
32422 COMPONENT_METADATA_DATA::NAME => Some(COMPONENT_METADATA_DATA::ID),
32423 WINCH_STATUS_DATA::NAME => Some(WINCH_STATUS_DATA::ID),
32424 TERRAIN_DATA_DATA::NAME => Some(TERRAIN_DATA_DATA::ID),
32425 DATA_TRANSMISSION_HANDSHAKE_DATA::NAME => Some(DATA_TRANSMISSION_HANDSHAKE_DATA::ID),
32426 ESC_INFO_DATA::NAME => Some(ESC_INFO_DATA::ID),
32427 SERVO_OUTPUT_RAW_DATA::NAME => Some(SERVO_OUTPUT_RAW_DATA::ID),
32428 PROTOCOL_VERSION_DATA::NAME => Some(PROTOCOL_VERSION_DATA::ID),
32429 MISSION_REQUEST_PARTIAL_LIST_DATA::NAME => Some(MISSION_REQUEST_PARTIAL_LIST_DATA::ID),
32430 SCALED_IMU2_DATA::NAME => Some(SCALED_IMU2_DATA::ID),
32431 DISTANCE_SENSOR_DATA::NAME => Some(DISTANCE_SENSOR_DATA::ID),
32432 SET_GPS_GLOBAL_ORIGIN_DATA::NAME => Some(SET_GPS_GLOBAL_ORIGIN_DATA::ID),
32433 ISBD_LINK_STATUS_DATA::NAME => Some(ISBD_LINK_STATUS_DATA::ID),
32434 EVENT_DATA::NAME => Some(EVENT_DATA::ID),
32435 GIMBAL_MANAGER_STATUS_DATA::NAME => Some(GIMBAL_MANAGER_STATUS_DATA::ID),
32436 PARAM_REQUEST_READ_DATA::NAME => Some(PARAM_REQUEST_READ_DATA::ID),
32437 STATUSTEXT_DATA::NAME => Some(STATUSTEXT_DATA::ID),
32438 CHANGE_OPERATOR_CONTROL_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_DATA::ID),
32439 EFI_STATUS_DATA::NAME => Some(EFI_STATUS_DATA::ID),
32440 LOG_REQUEST_END_DATA::NAME => Some(LOG_REQUEST_END_DATA::ID),
32441 GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME => Some(GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID),
32442 UAVCAN_NODE_INFO_DATA::NAME => Some(UAVCAN_NODE_INFO_DATA::ID),
32443 GPS_RTK_DATA::NAME => Some(GPS_RTK_DATA::ID),
32444 MISSION_REQUEST_INT_DATA::NAME => Some(MISSION_REQUEST_INT_DATA::ID),
32445 PING_DATA::NAME => Some(PING_DATA::ID),
32446 DEBUG_FLOAT_ARRAY_DATA::NAME => Some(DEBUG_FLOAT_ARRAY_DATA::ID),
32447 SETUP_SIGNING_DATA::NAME => Some(SETUP_SIGNING_DATA::ID),
32448 CAMERA_IMAGE_CAPTURED_DATA::NAME => Some(CAMERA_IMAGE_CAPTURED_DATA::ID),
32449 BATTERY_STATUS_DATA::NAME => Some(BATTERY_STATUS_DATA::ID),
32450 MISSION_COUNT_DATA::NAME => Some(MISSION_COUNT_DATA::ID),
32451 OPEN_DRONE_ID_ARM_STATUS_DATA::NAME => Some(OPEN_DRONE_ID_ARM_STATUS_DATA::ID),
32452 RC_CHANNELS_OVERRIDE_DATA::NAME => Some(RC_CHANNELS_OVERRIDE_DATA::ID),
32453 TERRAIN_REQUEST_DATA::NAME => Some(TERRAIN_REQUEST_DATA::ID),
32454 OBSTACLE_DISTANCE_DATA::NAME => Some(OBSTACLE_DISTANCE_DATA::ID),
32455 LANDING_TARGET_DATA::NAME => Some(LANDING_TARGET_DATA::ID),
32456 FOLLOW_TARGET_DATA::NAME => Some(FOLLOW_TARGET_DATA::ID),
32457 GLOBAL_POSITION_INT_COV_DATA::NAME => Some(GLOBAL_POSITION_INT_COV_DATA::ID),
32458 CONTROL_SYSTEM_STATE_DATA::NAME => Some(CONTROL_SYSTEM_STATE_DATA::ID),
32459 GPS_INPUT_DATA::NAME => Some(GPS_INPUT_DATA::ID),
32460 PLAY_TUNE_DATA::NAME => Some(PLAY_TUNE_DATA::ID),
32461 HIL_OPTICAL_FLOW_DATA::NAME => Some(HIL_OPTICAL_FLOW_DATA::ID),
32462 VISION_SPEED_ESTIMATE_DATA::NAME => Some(VISION_SPEED_ESTIMATE_DATA::ID),
32463 CAMERA_FOV_STATUS_DATA::NAME => Some(CAMERA_FOV_STATUS_DATA::ID),
32464 MISSION_ITEM_REACHED_DATA::NAME => Some(MISSION_ITEM_REACHED_DATA::ID),
32465 LOGGING_DATA_DATA::NAME => Some(LOGGING_DATA_DATA::ID),
32466 ONBOARD_COMPUTER_STATUS_DATA::NAME => Some(ONBOARD_COMPUTER_STATUS_DATA::ID),
32467 LOG_ERASE_DATA::NAME => Some(LOG_ERASE_DATA::ID),
32468 WHEEL_DISTANCE_DATA::NAME => Some(WHEEL_DISTANCE_DATA::ID),
32469 PARAM_EXT_VALUE_DATA::NAME => Some(PARAM_EXT_VALUE_DATA::ID),
32470 RC_CHANNELS_SCALED_DATA::NAME => Some(RC_CHANNELS_SCALED_DATA::ID),
32471 ATTITUDE_TARGET_DATA::NAME => Some(ATTITUDE_TARGET_DATA::ID),
32472 ATTITUDE_QUATERNION_DATA::NAME => Some(ATTITUDE_QUATERNION_DATA::ID),
32473 HIL_STATE_DATA::NAME => Some(HIL_STATE_DATA::ID),
32474 AUTOPILOT_VERSION_DATA::NAME => Some(AUTOPILOT_VERSION_DATA::ID),
32475 UAVCAN_NODE_STATUS_DATA::NAME => Some(UAVCAN_NODE_STATUS_DATA::ID),
32476 HIL_ACTUATOR_CONTROLS_DATA::NAME => Some(HIL_ACTUATOR_CONTROLS_DATA::ID),
32477 MISSION_ITEM_DATA::NAME => Some(MISSION_ITEM_DATA::ID),
32478 UTM_GLOBAL_POSITION_DATA::NAME => Some(UTM_GLOBAL_POSITION_DATA::ID),
32479 COMMAND_ACK_DATA::NAME => Some(COMMAND_ACK_DATA::ID),
32480 WIND_COV_DATA::NAME => Some(WIND_COV_DATA::ID),
32481 DEBUG_DATA::NAME => Some(DEBUG_DATA::ID),
32482 LOGGING_ACK_DATA::NAME => Some(LOGGING_ACK_DATA::ID),
32483 AVAILABLE_MODES_DATA::NAME => Some(AVAILABLE_MODES_DATA::ID),
32484 STORAGE_INFORMATION_DATA::NAME => Some(STORAGE_INFORMATION_DATA::ID),
32485 CAMERA_TRACKING_GEO_STATUS_DATA::NAME => Some(CAMERA_TRACKING_GEO_STATUS_DATA::ID),
32486 OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME => Some(OPEN_DRONE_ID_AUTHENTICATION_DATA::ID),
32487 ODOMETRY_DATA::NAME => Some(ODOMETRY_DATA::ID),
32488 SYSTEM_TIME_DATA::NAME => Some(SYSTEM_TIME_DATA::ID),
32489 VICON_POSITION_ESTIMATE_DATA::NAME => Some(VICON_POSITION_ESTIMATE_DATA::ID),
32490 CAN_FILTER_MODIFY_DATA::NAME => Some(CAN_FILTER_MODIFY_DATA::ID),
32491 OPTICAL_FLOW_RAD_DATA::NAME => Some(OPTICAL_FLOW_RAD_DATA::ID),
32492 SMART_BATTERY_INFO_DATA::NAME => Some(SMART_BATTERY_INFO_DATA::ID),
32493 PARAM_REQUEST_LIST_DATA::NAME => Some(PARAM_REQUEST_LIST_DATA::ID),
32494 LINK_NODE_STATUS_DATA::NAME => Some(LINK_NODE_STATUS_DATA::ID),
32495 OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME => Some(OPEN_DRONE_ID_OPERATOR_ID_DATA::ID),
32496 NAMED_VALUE_INT_DATA::NAME => Some(NAMED_VALUE_INT_DATA::ID),
32497 BATTERY_INFO_DATA::NAME => Some(BATTERY_INFO_DATA::ID),
32498 GPS_GLOBAL_ORIGIN_DATA::NAME => Some(GPS_GLOBAL_ORIGIN_DATA::ID),
32499 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME => {
32500 Some(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID)
32501 }
32502 HIL_STATE_QUATERNION_DATA::NAME => Some(HIL_STATE_QUATERNION_DATA::ID),
32503 DEBUG_VECT_DATA::NAME => Some(DEBUG_VECT_DATA::ID),
32504 VIDEO_STREAM_STATUS_DATA::NAME => Some(VIDEO_STREAM_STATUS_DATA::ID),
32505 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME => {
32506 Some(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID)
32507 }
32508 SET_POSITION_TARGET_LOCAL_NED_DATA::NAME => {
32509 Some(SET_POSITION_TARGET_LOCAL_NED_DATA::ID)
32510 }
32511 PARAM_EXT_ACK_DATA::NAME => Some(PARAM_EXT_ACK_DATA::ID),
32512 SAFETY_SET_ALLOWED_AREA_DATA::NAME => Some(SAFETY_SET_ALLOWED_AREA_DATA::ID),
32513 COMMAND_LONG_DATA::NAME => Some(COMMAND_LONG_DATA::ID),
32514 MOUNT_ORIENTATION_DATA::NAME => Some(MOUNT_ORIENTATION_DATA::ID),
32515 POWER_STATUS_DATA::NAME => Some(POWER_STATUS_DATA::ID),
32516 CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_ACK_DATA::ID),
32517 GPS_RAW_INT_DATA::NAME => Some(GPS_RAW_INT_DATA::ID),
32518 SIM_STATE_DATA::NAME => Some(SIM_STATE_DATA::ID),
32519 CELLULAR_CONFIG_DATA::NAME => Some(CELLULAR_CONFIG_DATA::ID),
32520 LOCAL_POSITION_NED_DATA::NAME => Some(LOCAL_POSITION_NED_DATA::ID),
32521 CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME => Some(CAMERA_TRACKING_IMAGE_STATUS_DATA::ID),
32522 TUNNEL_DATA::NAME => Some(TUNNEL_DATA::ID),
32523 RC_CHANNELS_DATA::NAME => Some(RC_CHANNELS_DATA::ID),
32524 NAMED_VALUE_FLOAT_DATA::NAME => Some(NAMED_VALUE_FLOAT_DATA::ID),
32525 SET_ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(SET_ACTUATOR_CONTROL_TARGET_DATA::ID),
32526 POSITION_TARGET_LOCAL_NED_DATA::NAME => Some(POSITION_TARGET_LOCAL_NED_DATA::ID),
32527 MEMORY_VECT_DATA::NAME => Some(MEMORY_VECT_DATA::ID),
32528 PARAM_EXT_REQUEST_LIST_DATA::NAME => Some(PARAM_EXT_REQUEST_LIST_DATA::ID),
32529 POSITION_TARGET_GLOBAL_INT_DATA::NAME => Some(POSITION_TARGET_GLOBAL_INT_DATA::ID),
32530 BUTTON_CHANGE_DATA::NAME => Some(BUTTON_CHANGE_DATA::ID),
32531 LOGGING_DATA_ACKED_DATA::NAME => Some(LOGGING_DATA_ACKED_DATA::ID),
32532 LOG_ENTRY_DATA::NAME => Some(LOG_ENTRY_DATA::ID),
32533 GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID),
32534 AIS_VESSEL_DATA::NAME => Some(AIS_VESSEL_DATA::ID),
32535 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME => {
32536 Some(TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID)
32537 }
32538 MAG_CAL_REPORT_DATA::NAME => Some(MAG_CAL_REPORT_DATA::ID),
32539 GPS2_RAW_DATA::NAME => Some(GPS2_RAW_DATA::ID),
32540 HEARTBEAT_DATA::NAME => Some(HEARTBEAT_DATA::ID),
32541 SYS_STATUS_DATA::NAME => Some(SYS_STATUS_DATA::ID),
32542 VIDEO_STREAM_INFORMATION_DATA::NAME => Some(VIDEO_STREAM_INFORMATION_DATA::ID),
32543 VIBRATION_DATA::NAME => Some(VIBRATION_DATA::ID),
32544 WIFI_CONFIG_AP_DATA::NAME => Some(WIFI_CONFIG_AP_DATA::ID),
32545 MISSION_REQUEST_LIST_DATA::NAME => Some(MISSION_REQUEST_LIST_DATA::ID),
32546 RAW_RPM_DATA::NAME => Some(RAW_RPM_DATA::ID),
32547 PLAY_TUNE_V2_DATA::NAME => Some(PLAY_TUNE_V2_DATA::ID),
32548 SUPPORTED_TUNES_DATA::NAME => Some(SUPPORTED_TUNES_DATA::ID),
32549 REQUEST_EVENT_DATA::NAME => Some(REQUEST_EVENT_DATA::ID),
32550 SCALED_PRESSURE_DATA::NAME => Some(SCALED_PRESSURE_DATA::ID),
32551 SCALED_PRESSURE3_DATA::NAME => Some(SCALED_PRESSURE3_DATA::ID),
32552 GIMBAL_DEVICE_INFORMATION_DATA::NAME => Some(GIMBAL_DEVICE_INFORMATION_DATA::ID),
32553 MISSION_WRITE_PARTIAL_LIST_DATA::NAME => Some(MISSION_WRITE_PARTIAL_LIST_DATA::ID),
32554 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID),
32555 CURRENT_EVENT_SEQUENCE_DATA::NAME => Some(CURRENT_EVENT_SEQUENCE_DATA::ID),
32556 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME => {
32557 Some(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID)
32558 }
32559 SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME => {
32560 Some(SET_POSITION_TARGET_GLOBAL_INT_DATA::ID)
32561 }
32562 _ => None,
32563 }
32564 }
32565 fn default_message_from_id(id: u32) -> Option<Self> {
32566 match id {
32567 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::default())),
32568 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::default())),
32569 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
32570 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
32571 GLOBAL_VISION_POSITION_ESTIMATE_DATA::default(),
32572 ))
32573 }
32574 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::default())),
32575 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
32576 TIME_ESTIMATE_TO_TARGET_DATA::default(),
32577 )),
32578 HIL_RC_INPUTS_RAW_DATA::ID => {
32579 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::default()))
32580 }
32581 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
32582 OPEN_DRONE_ID_MESSAGE_PACK_DATA::default(),
32583 )),
32584 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
32585 ATTITUDE_QUATERNION_COV_DATA::default(),
32586 )),
32587 GENERATOR_STATUS_DATA::ID => {
32588 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::default()))
32589 }
32590 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
32591 FILE_TRANSFER_PROTOCOL_DATA::default(),
32592 )),
32593 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
32594 ACTUATOR_OUTPUT_STATUS_DATA::default(),
32595 )),
32596 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
32597 COMPONENT_INFORMATION_BASIC_DATA::default(),
32598 )),
32599 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::default())),
32600 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
32601 OPEN_DRONE_ID_BASIC_ID_DATA::default(),
32602 )),
32603 ESTIMATOR_STATUS_DATA::ID => {
32604 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::default()))
32605 }
32606 MISSION_CURRENT_DATA::ID => {
32607 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::default()))
32608 }
32609 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
32610 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::default(),
32611 )),
32612 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
32613 GLOBAL_POSITION_INT_DATA::default(),
32614 )),
32615 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
32616 SET_ATTITUDE_TARGET_DATA::default(),
32617 )),
32618 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
32619 PARAM_EXT_REQUEST_READ_DATA::default(),
32620 )),
32621 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::default())),
32622 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::default())),
32623 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::default())),
32624 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
32625 OPEN_DRONE_ID_SELF_ID_DATA::default(),
32626 )),
32627 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
32628 LOCAL_POSITION_NED_COV_DATA::default(),
32629 )),
32630 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::default())),
32631 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::default())),
32632 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::default())),
32633 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::default())),
32634 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
32635 REQUEST_DATA_STREAM_DATA::default(),
32636 )),
32637 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::default())),
32638 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::default())),
32639 HYGROMETER_SENSOR_DATA::ID => {
32640 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::default()))
32641 }
32642 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
32643 COMPONENT_INFORMATION_DATA::default(),
32644 )),
32645 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::default())),
32646 SCALED_PRESSURE2_DATA::ID => {
32647 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::default()))
32648 }
32649 CAMERA_INFORMATION_DATA::ID => {
32650 Some(Self::CAMERA_INFORMATION(CAMERA_INFORMATION_DATA::default()))
32651 }
32652 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::default())),
32653 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::default())),
32654 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::default())),
32655 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::default())),
32656 MISSION_REQUEST_DATA::ID => {
32657 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::default()))
32658 }
32659 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::default())),
32660 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
32661 NAV_CONTROLLER_OUTPUT_DATA::default(),
32662 )),
32663 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::default())),
32664 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
32665 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
32666 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::default(),
32667 ))
32668 }
32669 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
32670 VISION_POSITION_ESTIMATE_DATA::default(),
32671 )),
32672 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::default())),
32673 CAMERA_SETTINGS_DATA::ID => {
32674 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::default()))
32675 }
32676 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::default())),
32677 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::default())),
32678 ENCAPSULATED_DATA_DATA::ID => {
32679 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::default()))
32680 }
32681 CELLULAR_STATUS_DATA::ID => {
32682 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::default()))
32683 }
32684 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::default())),
32685 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::default())),
32686 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::default())),
32687 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
32688 AVAILABLE_MODES_MONITOR_DATA::default(),
32689 )),
32690 ILLUMINATOR_STATUS_DATA::ID => {
32691 Some(Self::ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA::default()))
32692 }
32693 MISSION_ITEM_INT_DATA::ID => {
32694 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::default()))
32695 }
32696 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::default())),
32697 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::default())),
32698 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
32699 SAFETY_ALLOWED_AREA_DATA::default(),
32700 )),
32701 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::default())),
32702 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::default())),
32703 LOG_REQUEST_LIST_DATA::ID => {
32704 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::default()))
32705 }
32706 EXTENDED_SYS_STATE_DATA::ID => {
32707 Some(Self::EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA::default()))
32708 }
32709 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::default())),
32710 MESSAGE_INTERVAL_DATA::ID => {
32711 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::default()))
32712 }
32713 GPS_INJECT_DATA_DATA::ID => {
32714 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::default()))
32715 }
32716 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::default())),
32717 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::default())),
32718 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::default())),
32719 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
32720 OPEN_DRONE_ID_LOCATION_DATA::default(),
32721 )),
32722 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
32723 MISSION_SET_CURRENT_DATA::default(),
32724 )),
32725 MANUAL_SETPOINT_DATA::ID => {
32726 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::default()))
32727 }
32728 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::default())),
32729 FLIGHT_INFORMATION_DATA::ID => {
32730 Some(Self::FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA::default()))
32731 }
32732 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
32733 GIMBAL_MANAGER_INFORMATION_DATA::default(),
32734 )),
32735 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
32736 GIMBAL_MANAGER_SET_ATTITUDE_DATA::default(),
32737 )),
32738 RESOURCE_REQUEST_DATA::ID => {
32739 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::default()))
32740 }
32741 MISSION_CLEAR_ALL_DATA::ID => {
32742 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::default()))
32743 }
32744 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::default())),
32745 LOG_REQUEST_DATA_DATA::ID => {
32746 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::default()))
32747 }
32748 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
32749 CAMERA_THERMAL_RANGE_DATA::default(),
32750 )),
32751 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
32752 RESPONSE_EVENT_ERROR_DATA::default(),
32753 )),
32754 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::default())),
32755 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
32756 CAMERA_CAPTURE_STATUS_DATA::default(),
32757 )),
32758 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::default())),
32759 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
32760 ACTUATOR_CONTROL_TARGET_DATA::default(),
32761 )),
32762 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
32763 ORBIT_EXECUTION_STATUS_DATA::default(),
32764 )),
32765 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::default())),
32766 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
32767 OPEN_DRONE_ID_SYSTEM_DATA::default(),
32768 )),
32769 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::default())),
32770 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::default())),
32771 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::default())),
32772 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::default())),
32773 RC_CHANNELS_RAW_DATA::ID => {
32774 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::default()))
32775 }
32776 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::default())),
32777 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::default())),
32778 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::default())),
32779 SET_HOME_POSITION_DATA::ID => {
32780 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::default()))
32781 }
32782 COMPONENT_METADATA_DATA::ID => {
32783 Some(Self::COMPONENT_METADATA(COMPONENT_METADATA_DATA::default()))
32784 }
32785 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::default())),
32786 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::default())),
32787 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
32788 DATA_TRANSMISSION_HANDSHAKE_DATA::default(),
32789 )),
32790 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::default())),
32791 SERVO_OUTPUT_RAW_DATA::ID => {
32792 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::default()))
32793 }
32794 PROTOCOL_VERSION_DATA::ID => {
32795 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::default()))
32796 }
32797 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
32798 MISSION_REQUEST_PARTIAL_LIST_DATA::default(),
32799 )),
32800 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::default())),
32801 DISTANCE_SENSOR_DATA::ID => {
32802 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::default()))
32803 }
32804 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
32805 SET_GPS_GLOBAL_ORIGIN_DATA::default(),
32806 )),
32807 ISBD_LINK_STATUS_DATA::ID => {
32808 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::default()))
32809 }
32810 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::default())),
32811 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
32812 GIMBAL_MANAGER_STATUS_DATA::default(),
32813 )),
32814 PARAM_REQUEST_READ_DATA::ID => {
32815 Some(Self::PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA::default()))
32816 }
32817 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::default())),
32818 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
32819 CHANGE_OPERATOR_CONTROL_DATA::default(),
32820 )),
32821 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::default())),
32822 LOG_REQUEST_END_DATA::ID => {
32823 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::default()))
32824 }
32825 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
32826 GIMBAL_MANAGER_SET_PITCHYAW_DATA::default(),
32827 )),
32828 UAVCAN_NODE_INFO_DATA::ID => {
32829 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::default()))
32830 }
32831 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::default())),
32832 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
32833 MISSION_REQUEST_INT_DATA::default(),
32834 )),
32835 PING_DATA::ID => Some(Self::PING(PING_DATA::default())),
32836 DEBUG_FLOAT_ARRAY_DATA::ID => {
32837 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::default()))
32838 }
32839 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::default())),
32840 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
32841 CAMERA_IMAGE_CAPTURED_DATA::default(),
32842 )),
32843 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::default())),
32844 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::default())),
32845 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
32846 OPEN_DRONE_ID_ARM_STATUS_DATA::default(),
32847 )),
32848 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
32849 RC_CHANNELS_OVERRIDE_DATA::default(),
32850 )),
32851 TERRAIN_REQUEST_DATA::ID => {
32852 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::default()))
32853 }
32854 OBSTACLE_DISTANCE_DATA::ID => {
32855 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::default()))
32856 }
32857 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::default())),
32858 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::default())),
32859 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
32860 GLOBAL_POSITION_INT_COV_DATA::default(),
32861 )),
32862 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
32863 CONTROL_SYSTEM_STATE_DATA::default(),
32864 )),
32865 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::default())),
32866 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::default())),
32867 HIL_OPTICAL_FLOW_DATA::ID => {
32868 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::default()))
32869 }
32870 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
32871 VISION_SPEED_ESTIMATE_DATA::default(),
32872 )),
32873 CAMERA_FOV_STATUS_DATA::ID => {
32874 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::default()))
32875 }
32876 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
32877 MISSION_ITEM_REACHED_DATA::default(),
32878 )),
32879 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::default())),
32880 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
32881 ONBOARD_COMPUTER_STATUS_DATA::default(),
32882 )),
32883 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::default())),
32884 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::default())),
32885 PARAM_EXT_VALUE_DATA::ID => {
32886 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::default()))
32887 }
32888 RC_CHANNELS_SCALED_DATA::ID => {
32889 Some(Self::RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA::default()))
32890 }
32891 ATTITUDE_TARGET_DATA::ID => {
32892 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::default()))
32893 }
32894 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
32895 ATTITUDE_QUATERNION_DATA::default(),
32896 )),
32897 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::default())),
32898 AUTOPILOT_VERSION_DATA::ID => {
32899 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::default()))
32900 }
32901 UAVCAN_NODE_STATUS_DATA::ID => {
32902 Some(Self::UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA::default()))
32903 }
32904 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
32905 HIL_ACTUATOR_CONTROLS_DATA::default(),
32906 )),
32907 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::default())),
32908 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
32909 UTM_GLOBAL_POSITION_DATA::default(),
32910 )),
32911 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::default())),
32912 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::default())),
32913 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::default())),
32914 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::default())),
32915 AVAILABLE_MODES_DATA::ID => {
32916 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::default()))
32917 }
32918 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
32919 STORAGE_INFORMATION_DATA::default(),
32920 )),
32921 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
32922 CAMERA_TRACKING_GEO_STATUS_DATA::default(),
32923 )),
32924 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
32925 OPEN_DRONE_ID_AUTHENTICATION_DATA::default(),
32926 )),
32927 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::default())),
32928 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::default())),
32929 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
32930 VICON_POSITION_ESTIMATE_DATA::default(),
32931 )),
32932 CAN_FILTER_MODIFY_DATA::ID => {
32933 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::default()))
32934 }
32935 OPTICAL_FLOW_RAD_DATA::ID => {
32936 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::default()))
32937 }
32938 SMART_BATTERY_INFO_DATA::ID => {
32939 Some(Self::SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA::default()))
32940 }
32941 PARAM_REQUEST_LIST_DATA::ID => {
32942 Some(Self::PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA::default()))
32943 }
32944 LINK_NODE_STATUS_DATA::ID => {
32945 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::default()))
32946 }
32947 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
32948 OPEN_DRONE_ID_OPERATOR_ID_DATA::default(),
32949 )),
32950 NAMED_VALUE_INT_DATA::ID => {
32951 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::default()))
32952 }
32953 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::default())),
32954 GPS_GLOBAL_ORIGIN_DATA::ID => {
32955 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::default()))
32956 }
32957 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
32958 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
32959 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::default(),
32960 ))
32961 }
32962 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
32963 HIL_STATE_QUATERNION_DATA::default(),
32964 )),
32965 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::default())),
32966 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
32967 VIDEO_STREAM_STATUS_DATA::default(),
32968 )),
32969 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
32970 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
32971 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::default(),
32972 ))
32973 }
32974 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
32975 SET_POSITION_TARGET_LOCAL_NED_DATA::default(),
32976 )),
32977 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::default())),
32978 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
32979 SAFETY_SET_ALLOWED_AREA_DATA::default(),
32980 )),
32981 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::default())),
32982 MOUNT_ORIENTATION_DATA::ID => {
32983 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::default()))
32984 }
32985 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::default())),
32986 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
32987 CHANGE_OPERATOR_CONTROL_ACK_DATA::default(),
32988 )),
32989 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::default())),
32990 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::default())),
32991 CELLULAR_CONFIG_DATA::ID => {
32992 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::default()))
32993 }
32994 LOCAL_POSITION_NED_DATA::ID => {
32995 Some(Self::LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA::default()))
32996 }
32997 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
32998 CAMERA_TRACKING_IMAGE_STATUS_DATA::default(),
32999 )),
33000 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::default())),
33001 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::default())),
33002 NAMED_VALUE_FLOAT_DATA::ID => {
33003 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::default()))
33004 }
33005 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
33006 SET_ACTUATOR_CONTROL_TARGET_DATA::default(),
33007 )),
33008 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
33009 POSITION_TARGET_LOCAL_NED_DATA::default(),
33010 )),
33011 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::default())),
33012 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
33013 PARAM_EXT_REQUEST_LIST_DATA::default(),
33014 )),
33015 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
33016 POSITION_TARGET_GLOBAL_INT_DATA::default(),
33017 )),
33018 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::default())),
33019 LOGGING_DATA_ACKED_DATA::ID => {
33020 Some(Self::LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA::default()))
33021 }
33022 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::default())),
33023 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
33024 GIMBAL_DEVICE_SET_ATTITUDE_DATA::default(),
33025 )),
33026 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::default())),
33027 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
33028 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
33029 TRAJECTORY_REPRESENTATION_BEZIER_DATA::default(),
33030 ))
33031 }
33032 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::default())),
33033 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::default())),
33034 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::default())),
33035 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::default())),
33036 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
33037 VIDEO_STREAM_INFORMATION_DATA::default(),
33038 )),
33039 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::default())),
33040 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::default())),
33041 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
33042 MISSION_REQUEST_LIST_DATA::default(),
33043 )),
33044 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::default())),
33045 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::default())),
33046 SUPPORTED_TUNES_DATA::ID => {
33047 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::default()))
33048 }
33049 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::default())),
33050 SCALED_PRESSURE_DATA::ID => {
33051 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::default()))
33052 }
33053 SCALED_PRESSURE3_DATA::ID => {
33054 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::default()))
33055 }
33056 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
33057 GIMBAL_DEVICE_INFORMATION_DATA::default(),
33058 )),
33059 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
33060 MISSION_WRITE_PARTIAL_LIST_DATA::default(),
33061 )),
33062 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
33063 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::default(),
33064 )),
33065 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
33066 CURRENT_EVENT_SEQUENCE_DATA::default(),
33067 )),
33068 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
33069 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
33070 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::default(),
33071 ))
33072 }
33073 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
33074 SET_POSITION_TARGET_GLOBAL_INT_DATA::default(),
33075 )),
33076 _ => None,
33077 }
33078 }
33079 #[cfg(feature = "arbitrary")]
33080 fn random_message_from_id<R: rand::RngCore>(id: u32, rng: &mut R) -> Option<Self> {
33081 match id {
33082 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::random(rng))),
33083 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::random(rng))),
33084 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
33085 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
33086 GLOBAL_VISION_POSITION_ESTIMATE_DATA::random(rng),
33087 ))
33088 }
33089 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::random(rng))),
33090 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
33091 TIME_ESTIMATE_TO_TARGET_DATA::random(rng),
33092 )),
33093 HIL_RC_INPUTS_RAW_DATA::ID => {
33094 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::random(rng)))
33095 }
33096 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
33097 OPEN_DRONE_ID_MESSAGE_PACK_DATA::random(rng),
33098 )),
33099 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
33100 ATTITUDE_QUATERNION_COV_DATA::random(rng),
33101 )),
33102 GENERATOR_STATUS_DATA::ID => {
33103 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::random(rng)))
33104 }
33105 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
33106 FILE_TRANSFER_PROTOCOL_DATA::random(rng),
33107 )),
33108 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
33109 ACTUATOR_OUTPUT_STATUS_DATA::random(rng),
33110 )),
33111 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
33112 COMPONENT_INFORMATION_BASIC_DATA::random(rng),
33113 )),
33114 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::random(rng))),
33115 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
33116 OPEN_DRONE_ID_BASIC_ID_DATA::random(rng),
33117 )),
33118 ESTIMATOR_STATUS_DATA::ID => {
33119 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::random(rng)))
33120 }
33121 MISSION_CURRENT_DATA::ID => {
33122 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::random(rng)))
33123 }
33124 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
33125 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::random(rng),
33126 )),
33127 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
33128 GLOBAL_POSITION_INT_DATA::random(rng),
33129 )),
33130 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
33131 SET_ATTITUDE_TARGET_DATA::random(rng),
33132 )),
33133 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
33134 PARAM_EXT_REQUEST_READ_DATA::random(rng),
33135 )),
33136 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::random(rng))),
33137 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::random(rng))),
33138 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::random(rng))),
33139 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
33140 OPEN_DRONE_ID_SELF_ID_DATA::random(rng),
33141 )),
33142 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
33143 LOCAL_POSITION_NED_COV_DATA::random(rng),
33144 )),
33145 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::random(rng))),
33146 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::random(rng))),
33147 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::random(rng))),
33148 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::random(rng))),
33149 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
33150 REQUEST_DATA_STREAM_DATA::random(rng),
33151 )),
33152 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::random(rng))),
33153 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::random(rng))),
33154 HYGROMETER_SENSOR_DATA::ID => {
33155 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::random(rng)))
33156 }
33157 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
33158 COMPONENT_INFORMATION_DATA::random(rng),
33159 )),
33160 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::random(rng))),
33161 SCALED_PRESSURE2_DATA::ID => {
33162 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::random(rng)))
33163 }
33164 CAMERA_INFORMATION_DATA::ID => Some(Self::CAMERA_INFORMATION(
33165 CAMERA_INFORMATION_DATA::random(rng),
33166 )),
33167 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::random(rng))),
33168 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::random(rng))),
33169 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::random(rng))),
33170 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::random(rng))),
33171 MISSION_REQUEST_DATA::ID => {
33172 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::random(rng)))
33173 }
33174 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::random(rng))),
33175 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
33176 NAV_CONTROLLER_OUTPUT_DATA::random(rng),
33177 )),
33178 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::random(rng))),
33179 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
33180 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
33181 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::random(rng),
33182 ))
33183 }
33184 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
33185 VISION_POSITION_ESTIMATE_DATA::random(rng),
33186 )),
33187 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::random(rng))),
33188 CAMERA_SETTINGS_DATA::ID => {
33189 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::random(rng)))
33190 }
33191 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::random(rng))),
33192 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::random(rng))),
33193 ENCAPSULATED_DATA_DATA::ID => {
33194 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::random(rng)))
33195 }
33196 CELLULAR_STATUS_DATA::ID => {
33197 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::random(rng)))
33198 }
33199 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::random(rng))),
33200 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::random(rng))),
33201 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::random(rng))),
33202 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
33203 AVAILABLE_MODES_MONITOR_DATA::random(rng),
33204 )),
33205 ILLUMINATOR_STATUS_DATA::ID => Some(Self::ILLUMINATOR_STATUS(
33206 ILLUMINATOR_STATUS_DATA::random(rng),
33207 )),
33208 MISSION_ITEM_INT_DATA::ID => {
33209 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::random(rng)))
33210 }
33211 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::random(rng))),
33212 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::random(rng))),
33213 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
33214 SAFETY_ALLOWED_AREA_DATA::random(rng),
33215 )),
33216 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::random(rng))),
33217 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::random(rng))),
33218 LOG_REQUEST_LIST_DATA::ID => {
33219 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::random(rng)))
33220 }
33221 EXTENDED_SYS_STATE_DATA::ID => Some(Self::EXTENDED_SYS_STATE(
33222 EXTENDED_SYS_STATE_DATA::random(rng),
33223 )),
33224 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::random(rng))),
33225 MESSAGE_INTERVAL_DATA::ID => {
33226 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::random(rng)))
33227 }
33228 GPS_INJECT_DATA_DATA::ID => {
33229 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::random(rng)))
33230 }
33231 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::random(rng))),
33232 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::random(rng))),
33233 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::random(rng))),
33234 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
33235 OPEN_DRONE_ID_LOCATION_DATA::random(rng),
33236 )),
33237 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
33238 MISSION_SET_CURRENT_DATA::random(rng),
33239 )),
33240 MANUAL_SETPOINT_DATA::ID => {
33241 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::random(rng)))
33242 }
33243 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::random(rng))),
33244 FLIGHT_INFORMATION_DATA::ID => Some(Self::FLIGHT_INFORMATION(
33245 FLIGHT_INFORMATION_DATA::random(rng),
33246 )),
33247 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
33248 GIMBAL_MANAGER_INFORMATION_DATA::random(rng),
33249 )),
33250 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
33251 GIMBAL_MANAGER_SET_ATTITUDE_DATA::random(rng),
33252 )),
33253 RESOURCE_REQUEST_DATA::ID => {
33254 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::random(rng)))
33255 }
33256 MISSION_CLEAR_ALL_DATA::ID => {
33257 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::random(rng)))
33258 }
33259 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::random(rng))),
33260 LOG_REQUEST_DATA_DATA::ID => {
33261 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::random(rng)))
33262 }
33263 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
33264 CAMERA_THERMAL_RANGE_DATA::random(rng),
33265 )),
33266 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
33267 RESPONSE_EVENT_ERROR_DATA::random(rng),
33268 )),
33269 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::random(rng))),
33270 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
33271 CAMERA_CAPTURE_STATUS_DATA::random(rng),
33272 )),
33273 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::random(rng))),
33274 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
33275 ACTUATOR_CONTROL_TARGET_DATA::random(rng),
33276 )),
33277 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
33278 ORBIT_EXECUTION_STATUS_DATA::random(rng),
33279 )),
33280 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::random(rng))),
33281 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
33282 OPEN_DRONE_ID_SYSTEM_DATA::random(rng),
33283 )),
33284 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::random(rng))),
33285 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::random(rng))),
33286 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::random(rng))),
33287 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::random(rng))),
33288 RC_CHANNELS_RAW_DATA::ID => {
33289 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::random(rng)))
33290 }
33291 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::random(rng))),
33292 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::random(rng))),
33293 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::random(rng))),
33294 SET_HOME_POSITION_DATA::ID => {
33295 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::random(rng)))
33296 }
33297 COMPONENT_METADATA_DATA::ID => Some(Self::COMPONENT_METADATA(
33298 COMPONENT_METADATA_DATA::random(rng),
33299 )),
33300 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::random(rng))),
33301 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::random(rng))),
33302 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
33303 DATA_TRANSMISSION_HANDSHAKE_DATA::random(rng),
33304 )),
33305 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::random(rng))),
33306 SERVO_OUTPUT_RAW_DATA::ID => {
33307 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::random(rng)))
33308 }
33309 PROTOCOL_VERSION_DATA::ID => {
33310 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::random(rng)))
33311 }
33312 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
33313 MISSION_REQUEST_PARTIAL_LIST_DATA::random(rng),
33314 )),
33315 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::random(rng))),
33316 DISTANCE_SENSOR_DATA::ID => {
33317 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::random(rng)))
33318 }
33319 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
33320 SET_GPS_GLOBAL_ORIGIN_DATA::random(rng),
33321 )),
33322 ISBD_LINK_STATUS_DATA::ID => {
33323 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::random(rng)))
33324 }
33325 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::random(rng))),
33326 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
33327 GIMBAL_MANAGER_STATUS_DATA::random(rng),
33328 )),
33329 PARAM_REQUEST_READ_DATA::ID => Some(Self::PARAM_REQUEST_READ(
33330 PARAM_REQUEST_READ_DATA::random(rng),
33331 )),
33332 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::random(rng))),
33333 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
33334 CHANGE_OPERATOR_CONTROL_DATA::random(rng),
33335 )),
33336 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::random(rng))),
33337 LOG_REQUEST_END_DATA::ID => {
33338 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::random(rng)))
33339 }
33340 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
33341 GIMBAL_MANAGER_SET_PITCHYAW_DATA::random(rng),
33342 )),
33343 UAVCAN_NODE_INFO_DATA::ID => {
33344 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::random(rng)))
33345 }
33346 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::random(rng))),
33347 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
33348 MISSION_REQUEST_INT_DATA::random(rng),
33349 )),
33350 PING_DATA::ID => Some(Self::PING(PING_DATA::random(rng))),
33351 DEBUG_FLOAT_ARRAY_DATA::ID => {
33352 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::random(rng)))
33353 }
33354 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::random(rng))),
33355 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
33356 CAMERA_IMAGE_CAPTURED_DATA::random(rng),
33357 )),
33358 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::random(rng))),
33359 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::random(rng))),
33360 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
33361 OPEN_DRONE_ID_ARM_STATUS_DATA::random(rng),
33362 )),
33363 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
33364 RC_CHANNELS_OVERRIDE_DATA::random(rng),
33365 )),
33366 TERRAIN_REQUEST_DATA::ID => {
33367 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::random(rng)))
33368 }
33369 OBSTACLE_DISTANCE_DATA::ID => {
33370 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::random(rng)))
33371 }
33372 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::random(rng))),
33373 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::random(rng))),
33374 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
33375 GLOBAL_POSITION_INT_COV_DATA::random(rng),
33376 )),
33377 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
33378 CONTROL_SYSTEM_STATE_DATA::random(rng),
33379 )),
33380 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::random(rng))),
33381 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::random(rng))),
33382 HIL_OPTICAL_FLOW_DATA::ID => {
33383 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::random(rng)))
33384 }
33385 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
33386 VISION_SPEED_ESTIMATE_DATA::random(rng),
33387 )),
33388 CAMERA_FOV_STATUS_DATA::ID => {
33389 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::random(rng)))
33390 }
33391 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
33392 MISSION_ITEM_REACHED_DATA::random(rng),
33393 )),
33394 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::random(rng))),
33395 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
33396 ONBOARD_COMPUTER_STATUS_DATA::random(rng),
33397 )),
33398 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::random(rng))),
33399 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::random(rng))),
33400 PARAM_EXT_VALUE_DATA::ID => {
33401 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::random(rng)))
33402 }
33403 RC_CHANNELS_SCALED_DATA::ID => Some(Self::RC_CHANNELS_SCALED(
33404 RC_CHANNELS_SCALED_DATA::random(rng),
33405 )),
33406 ATTITUDE_TARGET_DATA::ID => {
33407 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::random(rng)))
33408 }
33409 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
33410 ATTITUDE_QUATERNION_DATA::random(rng),
33411 )),
33412 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::random(rng))),
33413 AUTOPILOT_VERSION_DATA::ID => {
33414 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::random(rng)))
33415 }
33416 UAVCAN_NODE_STATUS_DATA::ID => Some(Self::UAVCAN_NODE_STATUS(
33417 UAVCAN_NODE_STATUS_DATA::random(rng),
33418 )),
33419 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
33420 HIL_ACTUATOR_CONTROLS_DATA::random(rng),
33421 )),
33422 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::random(rng))),
33423 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
33424 UTM_GLOBAL_POSITION_DATA::random(rng),
33425 )),
33426 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::random(rng))),
33427 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::random(rng))),
33428 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::random(rng))),
33429 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::random(rng))),
33430 AVAILABLE_MODES_DATA::ID => {
33431 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::random(rng)))
33432 }
33433 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
33434 STORAGE_INFORMATION_DATA::random(rng),
33435 )),
33436 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
33437 CAMERA_TRACKING_GEO_STATUS_DATA::random(rng),
33438 )),
33439 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
33440 OPEN_DRONE_ID_AUTHENTICATION_DATA::random(rng),
33441 )),
33442 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::random(rng))),
33443 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::random(rng))),
33444 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
33445 VICON_POSITION_ESTIMATE_DATA::random(rng),
33446 )),
33447 CAN_FILTER_MODIFY_DATA::ID => {
33448 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::random(rng)))
33449 }
33450 OPTICAL_FLOW_RAD_DATA::ID => {
33451 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::random(rng)))
33452 }
33453 SMART_BATTERY_INFO_DATA::ID => Some(Self::SMART_BATTERY_INFO(
33454 SMART_BATTERY_INFO_DATA::random(rng),
33455 )),
33456 PARAM_REQUEST_LIST_DATA::ID => Some(Self::PARAM_REQUEST_LIST(
33457 PARAM_REQUEST_LIST_DATA::random(rng),
33458 )),
33459 LINK_NODE_STATUS_DATA::ID => {
33460 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::random(rng)))
33461 }
33462 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
33463 OPEN_DRONE_ID_OPERATOR_ID_DATA::random(rng),
33464 )),
33465 NAMED_VALUE_INT_DATA::ID => {
33466 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::random(rng)))
33467 }
33468 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::random(rng))),
33469 GPS_GLOBAL_ORIGIN_DATA::ID => {
33470 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::random(rng)))
33471 }
33472 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
33473 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
33474 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::random(rng),
33475 ))
33476 }
33477 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
33478 HIL_STATE_QUATERNION_DATA::random(rng),
33479 )),
33480 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::random(rng))),
33481 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
33482 VIDEO_STREAM_STATUS_DATA::random(rng),
33483 )),
33484 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
33485 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
33486 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::random(rng),
33487 ))
33488 }
33489 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
33490 SET_POSITION_TARGET_LOCAL_NED_DATA::random(rng),
33491 )),
33492 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::random(rng))),
33493 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
33494 SAFETY_SET_ALLOWED_AREA_DATA::random(rng),
33495 )),
33496 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::random(rng))),
33497 MOUNT_ORIENTATION_DATA::ID => {
33498 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::random(rng)))
33499 }
33500 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::random(rng))),
33501 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
33502 CHANGE_OPERATOR_CONTROL_ACK_DATA::random(rng),
33503 )),
33504 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::random(rng))),
33505 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::random(rng))),
33506 CELLULAR_CONFIG_DATA::ID => {
33507 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::random(rng)))
33508 }
33509 LOCAL_POSITION_NED_DATA::ID => Some(Self::LOCAL_POSITION_NED(
33510 LOCAL_POSITION_NED_DATA::random(rng),
33511 )),
33512 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
33513 CAMERA_TRACKING_IMAGE_STATUS_DATA::random(rng),
33514 )),
33515 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::random(rng))),
33516 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::random(rng))),
33517 NAMED_VALUE_FLOAT_DATA::ID => {
33518 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::random(rng)))
33519 }
33520 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
33521 SET_ACTUATOR_CONTROL_TARGET_DATA::random(rng),
33522 )),
33523 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
33524 POSITION_TARGET_LOCAL_NED_DATA::random(rng),
33525 )),
33526 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::random(rng))),
33527 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
33528 PARAM_EXT_REQUEST_LIST_DATA::random(rng),
33529 )),
33530 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
33531 POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
33532 )),
33533 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::random(rng))),
33534 LOGGING_DATA_ACKED_DATA::ID => Some(Self::LOGGING_DATA_ACKED(
33535 LOGGING_DATA_ACKED_DATA::random(rng),
33536 )),
33537 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::random(rng))),
33538 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
33539 GIMBAL_DEVICE_SET_ATTITUDE_DATA::random(rng),
33540 )),
33541 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::random(rng))),
33542 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
33543 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
33544 TRAJECTORY_REPRESENTATION_BEZIER_DATA::random(rng),
33545 ))
33546 }
33547 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::random(rng))),
33548 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::random(rng))),
33549 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::random(rng))),
33550 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::random(rng))),
33551 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
33552 VIDEO_STREAM_INFORMATION_DATA::random(rng),
33553 )),
33554 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::random(rng))),
33555 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::random(rng))),
33556 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
33557 MISSION_REQUEST_LIST_DATA::random(rng),
33558 )),
33559 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::random(rng))),
33560 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::random(rng))),
33561 SUPPORTED_TUNES_DATA::ID => {
33562 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::random(rng)))
33563 }
33564 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::random(rng))),
33565 SCALED_PRESSURE_DATA::ID => {
33566 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::random(rng)))
33567 }
33568 SCALED_PRESSURE3_DATA::ID => {
33569 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::random(rng)))
33570 }
33571 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
33572 GIMBAL_DEVICE_INFORMATION_DATA::random(rng),
33573 )),
33574 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
33575 MISSION_WRITE_PARTIAL_LIST_DATA::random(rng),
33576 )),
33577 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
33578 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::random(rng),
33579 )),
33580 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
33581 CURRENT_EVENT_SEQUENCE_DATA::random(rng),
33582 )),
33583 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
33584 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
33585 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::random(rng),
33586 ))
33587 }
33588 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
33589 SET_POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
33590 )),
33591 _ => None,
33592 }
33593 }
33594 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
33595 match self {
33596 Self::MANUAL_CONTROL(body) => body.ser(version, bytes),
33597 Self::V2_EXTENSION(body) => body.ser(version, bytes),
33598 Self::GLOBAL_VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
33599 Self::OPTICAL_FLOW(body) => body.ser(version, bytes),
33600 Self::TIME_ESTIMATE_TO_TARGET(body) => body.ser(version, bytes),
33601 Self::HIL_RC_INPUTS_RAW(body) => body.ser(version, bytes),
33602 Self::OPEN_DRONE_ID_MESSAGE_PACK(body) => body.ser(version, bytes),
33603 Self::ATTITUDE_QUATERNION_COV(body) => body.ser(version, bytes),
33604 Self::GENERATOR_STATUS(body) => body.ser(version, bytes),
33605 Self::FILE_TRANSFER_PROTOCOL(body) => body.ser(version, bytes),
33606 Self::ACTUATOR_OUTPUT_STATUS(body) => body.ser(version, bytes),
33607 Self::COMPONENT_INFORMATION_BASIC(body) => body.ser(version, bytes),
33608 Self::FUEL_STATUS(body) => body.ser(version, bytes),
33609 Self::OPEN_DRONE_ID_BASIC_ID(body) => body.ser(version, bytes),
33610 Self::ESTIMATOR_STATUS(body) => body.ser(version, bytes),
33611 Self::MISSION_CURRENT(body) => body.ser(version, bytes),
33612 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(body) => body.ser(version, bytes),
33613 Self::GLOBAL_POSITION_INT(body) => body.ser(version, bytes),
33614 Self::SET_ATTITUDE_TARGET(body) => body.ser(version, bytes),
33615 Self::PARAM_EXT_REQUEST_READ(body) => body.ser(version, bytes),
33616 Self::COLLISION(body) => body.ser(version, bytes),
33617 Self::GPS2_RTK(body) => body.ser(version, bytes),
33618 Self::COMMAND_INT(body) => body.ser(version, bytes),
33619 Self::OPEN_DRONE_ID_SELF_ID(body) => body.ser(version, bytes),
33620 Self::LOCAL_POSITION_NED_COV(body) => body.ser(version, bytes),
33621 Self::HIL_SENSOR(body) => body.ser(version, bytes),
33622 Self::SET_MODE(body) => body.ser(version, bytes),
33623 Self::RAW_PRESSURE(body) => body.ser(version, bytes),
33624 Self::TIMESYNC(body) => body.ser(version, bytes),
33625 Self::REQUEST_DATA_STREAM(body) => body.ser(version, bytes),
33626 Self::HIL_GPS(body) => body.ser(version, bytes),
33627 Self::CAN_FRAME(body) => body.ser(version, bytes),
33628 Self::HYGROMETER_SENSOR(body) => body.ser(version, bytes),
33629 Self::COMPONENT_INFORMATION(body) => body.ser(version, bytes),
33630 Self::TERRAIN_REPORT(body) => body.ser(version, bytes),
33631 Self::SCALED_PRESSURE2(body) => body.ser(version, bytes),
33632 Self::CAMERA_INFORMATION(body) => body.ser(version, bytes),
33633 Self::HIGH_LATENCY2(body) => body.ser(version, bytes),
33634 Self::ADSB_VEHICLE(body) => body.ser(version, bytes),
33635 Self::VFR_HUD(body) => body.ser(version, bytes),
33636 Self::ALTITUDE(body) => body.ser(version, bytes),
33637 Self::MISSION_REQUEST(body) => body.ser(version, bytes),
33638 Self::CANFD_FRAME(body) => body.ser(version, bytes),
33639 Self::NAV_CONTROLLER_OUTPUT(body) => body.ser(version, bytes),
33640 Self::HIL_CONTROLS(body) => body.ser(version, bytes),
33641 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(body) => body.ser(version, bytes),
33642 Self::VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
33643 Self::COMMAND_CANCEL(body) => body.ser(version, bytes),
33644 Self::CAMERA_SETTINGS(body) => body.ser(version, bytes),
33645 Self::GPS_STATUS(body) => body.ser(version, bytes),
33646 Self::ATTITUDE(body) => body.ser(version, bytes),
33647 Self::ENCAPSULATED_DATA(body) => body.ser(version, bytes),
33648 Self::CELLULAR_STATUS(body) => body.ser(version, bytes),
33649 Self::ESC_STATUS(body) => body.ser(version, bytes),
33650 Self::RAW_IMU(body) => body.ser(version, bytes),
33651 Self::HIGH_LATENCY(body) => body.ser(version, bytes),
33652 Self::AVAILABLE_MODES_MONITOR(body) => body.ser(version, bytes),
33653 Self::ILLUMINATOR_STATUS(body) => body.ser(version, bytes),
33654 Self::MISSION_ITEM_INT(body) => body.ser(version, bytes),
33655 Self::CURRENT_MODE(body) => body.ser(version, bytes),
33656 Self::SCALED_IMU(body) => body.ser(version, bytes),
33657 Self::SAFETY_ALLOWED_AREA(body) => body.ser(version, bytes),
33658 Self::TERRAIN_CHECK(body) => body.ser(version, bytes),
33659 Self::DATA_STREAM(body) => body.ser(version, bytes),
33660 Self::LOG_REQUEST_LIST(body) => body.ser(version, bytes),
33661 Self::EXTENDED_SYS_STATE(body) => body.ser(version, bytes),
33662 Self::CAMERA_TRIGGER(body) => body.ser(version, bytes),
33663 Self::MESSAGE_INTERVAL(body) => body.ser(version, bytes),
33664 Self::GPS_INJECT_DATA(body) => body.ser(version, bytes),
33665 Self::HOME_POSITION(body) => body.ser(version, bytes),
33666 Self::PARAM_MAP_RC(body) => body.ser(version, bytes),
33667 Self::SERIAL_CONTROL(body) => body.ser(version, bytes),
33668 Self::OPEN_DRONE_ID_LOCATION(body) => body.ser(version, bytes),
33669 Self::MISSION_SET_CURRENT(body) => body.ser(version, bytes),
33670 Self::MANUAL_SETPOINT(body) => body.ser(version, bytes),
33671 Self::FENCE_STATUS(body) => body.ser(version, bytes),
33672 Self::FLIGHT_INFORMATION(body) => body.ser(version, bytes),
33673 Self::GIMBAL_MANAGER_INFORMATION(body) => body.ser(version, bytes),
33674 Self::GIMBAL_MANAGER_SET_ATTITUDE(body) => body.ser(version, bytes),
33675 Self::RESOURCE_REQUEST(body) => body.ser(version, bytes),
33676 Self::MISSION_CLEAR_ALL(body) => body.ser(version, bytes),
33677 Self::PARAM_SET(body) => body.ser(version, bytes),
33678 Self::LOG_REQUEST_DATA(body) => body.ser(version, bytes),
33679 Self::CAMERA_THERMAL_RANGE(body) => body.ser(version, bytes),
33680 Self::RESPONSE_EVENT_ERROR(body) => body.ser(version, bytes),
33681 Self::SCALED_IMU3(body) => body.ser(version, bytes),
33682 Self::CAMERA_CAPTURE_STATUS(body) => body.ser(version, bytes),
33683 Self::PARAM_EXT_SET(body) => body.ser(version, bytes),
33684 Self::ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
33685 Self::ORBIT_EXECUTION_STATUS(body) => body.ser(version, bytes),
33686 Self::HIGHRES_IMU(body) => body.ser(version, bytes),
33687 Self::OPEN_DRONE_ID_SYSTEM(body) => body.ser(version, bytes),
33688 Self::MISSION_ACK(body) => body.ser(version, bytes),
33689 Self::GPS_RTCM_DATA(body) => body.ser(version, bytes),
33690 Self::RADIO_STATUS(body) => body.ser(version, bytes),
33691 Self::AUTH_KEY(body) => body.ser(version, bytes),
33692 Self::RC_CHANNELS_RAW(body) => body.ser(version, bytes),
33693 Self::LOG_DATA(body) => body.ser(version, bytes),
33694 Self::PARAM_VALUE(body) => body.ser(version, bytes),
33695 Self::ATT_POS_MOCAP(body) => body.ser(version, bytes),
33696 Self::SET_HOME_POSITION(body) => body.ser(version, bytes),
33697 Self::COMPONENT_METADATA(body) => body.ser(version, bytes),
33698 Self::WINCH_STATUS(body) => body.ser(version, bytes),
33699 Self::TERRAIN_DATA(body) => body.ser(version, bytes),
33700 Self::DATA_TRANSMISSION_HANDSHAKE(body) => body.ser(version, bytes),
33701 Self::ESC_INFO(body) => body.ser(version, bytes),
33702 Self::SERVO_OUTPUT_RAW(body) => body.ser(version, bytes),
33703 Self::PROTOCOL_VERSION(body) => body.ser(version, bytes),
33704 Self::MISSION_REQUEST_PARTIAL_LIST(body) => body.ser(version, bytes),
33705 Self::SCALED_IMU2(body) => body.ser(version, bytes),
33706 Self::DISTANCE_SENSOR(body) => body.ser(version, bytes),
33707 Self::SET_GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
33708 Self::ISBD_LINK_STATUS(body) => body.ser(version, bytes),
33709 Self::EVENT(body) => body.ser(version, bytes),
33710 Self::GIMBAL_MANAGER_STATUS(body) => body.ser(version, bytes),
33711 Self::PARAM_REQUEST_READ(body) => body.ser(version, bytes),
33712 Self::STATUSTEXT(body) => body.ser(version, bytes),
33713 Self::CHANGE_OPERATOR_CONTROL(body) => body.ser(version, bytes),
33714 Self::EFI_STATUS(body) => body.ser(version, bytes),
33715 Self::LOG_REQUEST_END(body) => body.ser(version, bytes),
33716 Self::GIMBAL_MANAGER_SET_PITCHYAW(body) => body.ser(version, bytes),
33717 Self::UAVCAN_NODE_INFO(body) => body.ser(version, bytes),
33718 Self::GPS_RTK(body) => body.ser(version, bytes),
33719 Self::MISSION_REQUEST_INT(body) => body.ser(version, bytes),
33720 Self::PING(body) => body.ser(version, bytes),
33721 Self::DEBUG_FLOAT_ARRAY(body) => body.ser(version, bytes),
33722 Self::SETUP_SIGNING(body) => body.ser(version, bytes),
33723 Self::CAMERA_IMAGE_CAPTURED(body) => body.ser(version, bytes),
33724 Self::BATTERY_STATUS(body) => body.ser(version, bytes),
33725 Self::MISSION_COUNT(body) => body.ser(version, bytes),
33726 Self::OPEN_DRONE_ID_ARM_STATUS(body) => body.ser(version, bytes),
33727 Self::RC_CHANNELS_OVERRIDE(body) => body.ser(version, bytes),
33728 Self::TERRAIN_REQUEST(body) => body.ser(version, bytes),
33729 Self::OBSTACLE_DISTANCE(body) => body.ser(version, bytes),
33730 Self::LANDING_TARGET(body) => body.ser(version, bytes),
33731 Self::FOLLOW_TARGET(body) => body.ser(version, bytes),
33732 Self::GLOBAL_POSITION_INT_COV(body) => body.ser(version, bytes),
33733 Self::CONTROL_SYSTEM_STATE(body) => body.ser(version, bytes),
33734 Self::GPS_INPUT(body) => body.ser(version, bytes),
33735 Self::PLAY_TUNE(body) => body.ser(version, bytes),
33736 Self::HIL_OPTICAL_FLOW(body) => body.ser(version, bytes),
33737 Self::VISION_SPEED_ESTIMATE(body) => body.ser(version, bytes),
33738 Self::CAMERA_FOV_STATUS(body) => body.ser(version, bytes),
33739 Self::MISSION_ITEM_REACHED(body) => body.ser(version, bytes),
33740 Self::LOGGING_DATA(body) => body.ser(version, bytes),
33741 Self::ONBOARD_COMPUTER_STATUS(body) => body.ser(version, bytes),
33742 Self::LOG_ERASE(body) => body.ser(version, bytes),
33743 Self::WHEEL_DISTANCE(body) => body.ser(version, bytes),
33744 Self::PARAM_EXT_VALUE(body) => body.ser(version, bytes),
33745 Self::RC_CHANNELS_SCALED(body) => body.ser(version, bytes),
33746 Self::ATTITUDE_TARGET(body) => body.ser(version, bytes),
33747 Self::ATTITUDE_QUATERNION(body) => body.ser(version, bytes),
33748 Self::HIL_STATE(body) => body.ser(version, bytes),
33749 Self::AUTOPILOT_VERSION(body) => body.ser(version, bytes),
33750 Self::UAVCAN_NODE_STATUS(body) => body.ser(version, bytes),
33751 Self::HIL_ACTUATOR_CONTROLS(body) => body.ser(version, bytes),
33752 Self::MISSION_ITEM(body) => body.ser(version, bytes),
33753 Self::UTM_GLOBAL_POSITION(body) => body.ser(version, bytes),
33754 Self::COMMAND_ACK(body) => body.ser(version, bytes),
33755 Self::WIND_COV(body) => body.ser(version, bytes),
33756 Self::DEBUG(body) => body.ser(version, bytes),
33757 Self::LOGGING_ACK(body) => body.ser(version, bytes),
33758 Self::AVAILABLE_MODES(body) => body.ser(version, bytes),
33759 Self::STORAGE_INFORMATION(body) => body.ser(version, bytes),
33760 Self::CAMERA_TRACKING_GEO_STATUS(body) => body.ser(version, bytes),
33761 Self::OPEN_DRONE_ID_AUTHENTICATION(body) => body.ser(version, bytes),
33762 Self::ODOMETRY(body) => body.ser(version, bytes),
33763 Self::SYSTEM_TIME(body) => body.ser(version, bytes),
33764 Self::VICON_POSITION_ESTIMATE(body) => body.ser(version, bytes),
33765 Self::CAN_FILTER_MODIFY(body) => body.ser(version, bytes),
33766 Self::OPTICAL_FLOW_RAD(body) => body.ser(version, bytes),
33767 Self::SMART_BATTERY_INFO(body) => body.ser(version, bytes),
33768 Self::PARAM_REQUEST_LIST(body) => body.ser(version, bytes),
33769 Self::LINK_NODE_STATUS(body) => body.ser(version, bytes),
33770 Self::OPEN_DRONE_ID_OPERATOR_ID(body) => body.ser(version, bytes),
33771 Self::NAMED_VALUE_INT(body) => body.ser(version, bytes),
33772 Self::BATTERY_INFO(body) => body.ser(version, bytes),
33773 Self::GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
33774 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(body) => body.ser(version, bytes),
33775 Self::HIL_STATE_QUATERNION(body) => body.ser(version, bytes),
33776 Self::DEBUG_VECT(body) => body.ser(version, bytes),
33777 Self::VIDEO_STREAM_STATUS(body) => body.ser(version, bytes),
33778 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(body) => body.ser(version, bytes),
33779 Self::SET_POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
33780 Self::PARAM_EXT_ACK(body) => body.ser(version, bytes),
33781 Self::SAFETY_SET_ALLOWED_AREA(body) => body.ser(version, bytes),
33782 Self::COMMAND_LONG(body) => body.ser(version, bytes),
33783 Self::MOUNT_ORIENTATION(body) => body.ser(version, bytes),
33784 Self::POWER_STATUS(body) => body.ser(version, bytes),
33785 Self::CHANGE_OPERATOR_CONTROL_ACK(body) => body.ser(version, bytes),
33786 Self::GPS_RAW_INT(body) => body.ser(version, bytes),
33787 Self::SIM_STATE(body) => body.ser(version, bytes),
33788 Self::CELLULAR_CONFIG(body) => body.ser(version, bytes),
33789 Self::LOCAL_POSITION_NED(body) => body.ser(version, bytes),
33790 Self::CAMERA_TRACKING_IMAGE_STATUS(body) => body.ser(version, bytes),
33791 Self::TUNNEL(body) => body.ser(version, bytes),
33792 Self::RC_CHANNELS(body) => body.ser(version, bytes),
33793 Self::NAMED_VALUE_FLOAT(body) => body.ser(version, bytes),
33794 Self::SET_ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
33795 Self::POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
33796 Self::MEMORY_VECT(body) => body.ser(version, bytes),
33797 Self::PARAM_EXT_REQUEST_LIST(body) => body.ser(version, bytes),
33798 Self::POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
33799 Self::BUTTON_CHANGE(body) => body.ser(version, bytes),
33800 Self::LOGGING_DATA_ACKED(body) => body.ser(version, bytes),
33801 Self::LOG_ENTRY(body) => body.ser(version, bytes),
33802 Self::GIMBAL_DEVICE_SET_ATTITUDE(body) => body.ser(version, bytes),
33803 Self::AIS_VESSEL(body) => body.ser(version, bytes),
33804 Self::TRAJECTORY_REPRESENTATION_BEZIER(body) => body.ser(version, bytes),
33805 Self::MAG_CAL_REPORT(body) => body.ser(version, bytes),
33806 Self::GPS2_RAW(body) => body.ser(version, bytes),
33807 Self::HEARTBEAT(body) => body.ser(version, bytes),
33808 Self::SYS_STATUS(body) => body.ser(version, bytes),
33809 Self::VIDEO_STREAM_INFORMATION(body) => body.ser(version, bytes),
33810 Self::VIBRATION(body) => body.ser(version, bytes),
33811 Self::WIFI_CONFIG_AP(body) => body.ser(version, bytes),
33812 Self::MISSION_REQUEST_LIST(body) => body.ser(version, bytes),
33813 Self::RAW_RPM(body) => body.ser(version, bytes),
33814 Self::PLAY_TUNE_V2(body) => body.ser(version, bytes),
33815 Self::SUPPORTED_TUNES(body) => body.ser(version, bytes),
33816 Self::REQUEST_EVENT(body) => body.ser(version, bytes),
33817 Self::SCALED_PRESSURE(body) => body.ser(version, bytes),
33818 Self::SCALED_PRESSURE3(body) => body.ser(version, bytes),
33819 Self::GIMBAL_DEVICE_INFORMATION(body) => body.ser(version, bytes),
33820 Self::MISSION_WRITE_PARTIAL_LIST(body) => body.ser(version, bytes),
33821 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(body) => body.ser(version, bytes),
33822 Self::CURRENT_EVENT_SEQUENCE(body) => body.ser(version, bytes),
33823 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(body) => body.ser(version, bytes),
33824 Self::SET_POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
33825 }
33826 }
33827 fn extra_crc(id: u32) -> u8 {
33828 match id {
33829 MANUAL_CONTROL_DATA::ID => MANUAL_CONTROL_DATA::EXTRA_CRC,
33830 V2_EXTENSION_DATA::ID => V2_EXTENSION_DATA::EXTRA_CRC,
33831 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
33832 GLOBAL_VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC
33833 }
33834 OPTICAL_FLOW_DATA::ID => OPTICAL_FLOW_DATA::EXTRA_CRC,
33835 TIME_ESTIMATE_TO_TARGET_DATA::ID => TIME_ESTIMATE_TO_TARGET_DATA::EXTRA_CRC,
33836 HIL_RC_INPUTS_RAW_DATA::ID => HIL_RC_INPUTS_RAW_DATA::EXTRA_CRC,
33837 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => OPEN_DRONE_ID_MESSAGE_PACK_DATA::EXTRA_CRC,
33838 ATTITUDE_QUATERNION_COV_DATA::ID => ATTITUDE_QUATERNION_COV_DATA::EXTRA_CRC,
33839 GENERATOR_STATUS_DATA::ID => GENERATOR_STATUS_DATA::EXTRA_CRC,
33840 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::EXTRA_CRC,
33841 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::EXTRA_CRC,
33842 COMPONENT_INFORMATION_BASIC_DATA::ID => COMPONENT_INFORMATION_BASIC_DATA::EXTRA_CRC,
33843 FUEL_STATUS_DATA::ID => FUEL_STATUS_DATA::EXTRA_CRC,
33844 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::EXTRA_CRC,
33845 ESTIMATOR_STATUS_DATA::ID => ESTIMATOR_STATUS_DATA::EXTRA_CRC,
33846 MISSION_CURRENT_DATA::ID => MISSION_CURRENT_DATA::EXTRA_CRC,
33847 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::EXTRA_CRC,
33848 GLOBAL_POSITION_INT_DATA::ID => GLOBAL_POSITION_INT_DATA::EXTRA_CRC,
33849 SET_ATTITUDE_TARGET_DATA::ID => SET_ATTITUDE_TARGET_DATA::EXTRA_CRC,
33850 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::EXTRA_CRC,
33851 COLLISION_DATA::ID => COLLISION_DATA::EXTRA_CRC,
33852 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::EXTRA_CRC,
33853 COMMAND_INT_DATA::ID => COMMAND_INT_DATA::EXTRA_CRC,
33854 OPEN_DRONE_ID_SELF_ID_DATA::ID => OPEN_DRONE_ID_SELF_ID_DATA::EXTRA_CRC,
33855 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::EXTRA_CRC,
33856 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::EXTRA_CRC,
33857 SET_MODE_DATA::ID => SET_MODE_DATA::EXTRA_CRC,
33858 RAW_PRESSURE_DATA::ID => RAW_PRESSURE_DATA::EXTRA_CRC,
33859 TIMESYNC_DATA::ID => TIMESYNC_DATA::EXTRA_CRC,
33860 REQUEST_DATA_STREAM_DATA::ID => REQUEST_DATA_STREAM_DATA::EXTRA_CRC,
33861 HIL_GPS_DATA::ID => HIL_GPS_DATA::EXTRA_CRC,
33862 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::EXTRA_CRC,
33863 HYGROMETER_SENSOR_DATA::ID => HYGROMETER_SENSOR_DATA::EXTRA_CRC,
33864 COMPONENT_INFORMATION_DATA::ID => COMPONENT_INFORMATION_DATA::EXTRA_CRC,
33865 TERRAIN_REPORT_DATA::ID => TERRAIN_REPORT_DATA::EXTRA_CRC,
33866 SCALED_PRESSURE2_DATA::ID => SCALED_PRESSURE2_DATA::EXTRA_CRC,
33867 CAMERA_INFORMATION_DATA::ID => CAMERA_INFORMATION_DATA::EXTRA_CRC,
33868 HIGH_LATENCY2_DATA::ID => HIGH_LATENCY2_DATA::EXTRA_CRC,
33869 ADSB_VEHICLE_DATA::ID => ADSB_VEHICLE_DATA::EXTRA_CRC,
33870 VFR_HUD_DATA::ID => VFR_HUD_DATA::EXTRA_CRC,
33871 ALTITUDE_DATA::ID => ALTITUDE_DATA::EXTRA_CRC,
33872 MISSION_REQUEST_DATA::ID => MISSION_REQUEST_DATA::EXTRA_CRC,
33873 CANFD_FRAME_DATA::ID => CANFD_FRAME_DATA::EXTRA_CRC,
33874 NAV_CONTROLLER_OUTPUT_DATA::ID => NAV_CONTROLLER_OUTPUT_DATA::EXTRA_CRC,
33875 HIL_CONTROLS_DATA::ID => HIL_CONTROLS_DATA::EXTRA_CRC,
33876 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
33877 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::EXTRA_CRC
33878 }
33879 VISION_POSITION_ESTIMATE_DATA::ID => VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC,
33880 COMMAND_CANCEL_DATA::ID => COMMAND_CANCEL_DATA::EXTRA_CRC,
33881 CAMERA_SETTINGS_DATA::ID => CAMERA_SETTINGS_DATA::EXTRA_CRC,
33882 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::EXTRA_CRC,
33883 ATTITUDE_DATA::ID => ATTITUDE_DATA::EXTRA_CRC,
33884 ENCAPSULATED_DATA_DATA::ID => ENCAPSULATED_DATA_DATA::EXTRA_CRC,
33885 CELLULAR_STATUS_DATA::ID => CELLULAR_STATUS_DATA::EXTRA_CRC,
33886 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::EXTRA_CRC,
33887 RAW_IMU_DATA::ID => RAW_IMU_DATA::EXTRA_CRC,
33888 HIGH_LATENCY_DATA::ID => HIGH_LATENCY_DATA::EXTRA_CRC,
33889 AVAILABLE_MODES_MONITOR_DATA::ID => AVAILABLE_MODES_MONITOR_DATA::EXTRA_CRC,
33890 ILLUMINATOR_STATUS_DATA::ID => ILLUMINATOR_STATUS_DATA::EXTRA_CRC,
33891 MISSION_ITEM_INT_DATA::ID => MISSION_ITEM_INT_DATA::EXTRA_CRC,
33892 CURRENT_MODE_DATA::ID => CURRENT_MODE_DATA::EXTRA_CRC,
33893 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::EXTRA_CRC,
33894 SAFETY_ALLOWED_AREA_DATA::ID => SAFETY_ALLOWED_AREA_DATA::EXTRA_CRC,
33895 TERRAIN_CHECK_DATA::ID => TERRAIN_CHECK_DATA::EXTRA_CRC,
33896 DATA_STREAM_DATA::ID => DATA_STREAM_DATA::EXTRA_CRC,
33897 LOG_REQUEST_LIST_DATA::ID => LOG_REQUEST_LIST_DATA::EXTRA_CRC,
33898 EXTENDED_SYS_STATE_DATA::ID => EXTENDED_SYS_STATE_DATA::EXTRA_CRC,
33899 CAMERA_TRIGGER_DATA::ID => CAMERA_TRIGGER_DATA::EXTRA_CRC,
33900 MESSAGE_INTERVAL_DATA::ID => MESSAGE_INTERVAL_DATA::EXTRA_CRC,
33901 GPS_INJECT_DATA_DATA::ID => GPS_INJECT_DATA_DATA::EXTRA_CRC,
33902 HOME_POSITION_DATA::ID => HOME_POSITION_DATA::EXTRA_CRC,
33903 PARAM_MAP_RC_DATA::ID => PARAM_MAP_RC_DATA::EXTRA_CRC,
33904 SERIAL_CONTROL_DATA::ID => SERIAL_CONTROL_DATA::EXTRA_CRC,
33905 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::EXTRA_CRC,
33906 MISSION_SET_CURRENT_DATA::ID => MISSION_SET_CURRENT_DATA::EXTRA_CRC,
33907 MANUAL_SETPOINT_DATA::ID => MANUAL_SETPOINT_DATA::EXTRA_CRC,
33908 FENCE_STATUS_DATA::ID => FENCE_STATUS_DATA::EXTRA_CRC,
33909 FLIGHT_INFORMATION_DATA::ID => FLIGHT_INFORMATION_DATA::EXTRA_CRC,
33910 GIMBAL_MANAGER_INFORMATION_DATA::ID => GIMBAL_MANAGER_INFORMATION_DATA::EXTRA_CRC,
33911 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => GIMBAL_MANAGER_SET_ATTITUDE_DATA::EXTRA_CRC,
33912 RESOURCE_REQUEST_DATA::ID => RESOURCE_REQUEST_DATA::EXTRA_CRC,
33913 MISSION_CLEAR_ALL_DATA::ID => MISSION_CLEAR_ALL_DATA::EXTRA_CRC,
33914 PARAM_SET_DATA::ID => PARAM_SET_DATA::EXTRA_CRC,
33915 LOG_REQUEST_DATA_DATA::ID => LOG_REQUEST_DATA_DATA::EXTRA_CRC,
33916 CAMERA_THERMAL_RANGE_DATA::ID => CAMERA_THERMAL_RANGE_DATA::EXTRA_CRC,
33917 RESPONSE_EVENT_ERROR_DATA::ID => RESPONSE_EVENT_ERROR_DATA::EXTRA_CRC,
33918 SCALED_IMU3_DATA::ID => SCALED_IMU3_DATA::EXTRA_CRC,
33919 CAMERA_CAPTURE_STATUS_DATA::ID => CAMERA_CAPTURE_STATUS_DATA::EXTRA_CRC,
33920 PARAM_EXT_SET_DATA::ID => PARAM_EXT_SET_DATA::EXTRA_CRC,
33921 ACTUATOR_CONTROL_TARGET_DATA::ID => ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
33922 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::EXTRA_CRC,
33923 HIGHRES_IMU_DATA::ID => HIGHRES_IMU_DATA::EXTRA_CRC,
33924 OPEN_DRONE_ID_SYSTEM_DATA::ID => OPEN_DRONE_ID_SYSTEM_DATA::EXTRA_CRC,
33925 MISSION_ACK_DATA::ID => MISSION_ACK_DATA::EXTRA_CRC,
33926 GPS_RTCM_DATA_DATA::ID => GPS_RTCM_DATA_DATA::EXTRA_CRC,
33927 RADIO_STATUS_DATA::ID => RADIO_STATUS_DATA::EXTRA_CRC,
33928 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::EXTRA_CRC,
33929 RC_CHANNELS_RAW_DATA::ID => RC_CHANNELS_RAW_DATA::EXTRA_CRC,
33930 LOG_DATA_DATA::ID => LOG_DATA_DATA::EXTRA_CRC,
33931 PARAM_VALUE_DATA::ID => PARAM_VALUE_DATA::EXTRA_CRC,
33932 ATT_POS_MOCAP_DATA::ID => ATT_POS_MOCAP_DATA::EXTRA_CRC,
33933 SET_HOME_POSITION_DATA::ID => SET_HOME_POSITION_DATA::EXTRA_CRC,
33934 COMPONENT_METADATA_DATA::ID => COMPONENT_METADATA_DATA::EXTRA_CRC,
33935 WINCH_STATUS_DATA::ID => WINCH_STATUS_DATA::EXTRA_CRC,
33936 TERRAIN_DATA_DATA::ID => TERRAIN_DATA_DATA::EXTRA_CRC,
33937 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => DATA_TRANSMISSION_HANDSHAKE_DATA::EXTRA_CRC,
33938 ESC_INFO_DATA::ID => ESC_INFO_DATA::EXTRA_CRC,
33939 SERVO_OUTPUT_RAW_DATA::ID => SERVO_OUTPUT_RAW_DATA::EXTRA_CRC,
33940 PROTOCOL_VERSION_DATA::ID => PROTOCOL_VERSION_DATA::EXTRA_CRC,
33941 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => MISSION_REQUEST_PARTIAL_LIST_DATA::EXTRA_CRC,
33942 SCALED_IMU2_DATA::ID => SCALED_IMU2_DATA::EXTRA_CRC,
33943 DISTANCE_SENSOR_DATA::ID => DISTANCE_SENSOR_DATA::EXTRA_CRC,
33944 SET_GPS_GLOBAL_ORIGIN_DATA::ID => SET_GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
33945 ISBD_LINK_STATUS_DATA::ID => ISBD_LINK_STATUS_DATA::EXTRA_CRC,
33946 EVENT_DATA::ID => EVENT_DATA::EXTRA_CRC,
33947 GIMBAL_MANAGER_STATUS_DATA::ID => GIMBAL_MANAGER_STATUS_DATA::EXTRA_CRC,
33948 PARAM_REQUEST_READ_DATA::ID => PARAM_REQUEST_READ_DATA::EXTRA_CRC,
33949 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::EXTRA_CRC,
33950 CHANGE_OPERATOR_CONTROL_DATA::ID => CHANGE_OPERATOR_CONTROL_DATA::EXTRA_CRC,
33951 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::EXTRA_CRC,
33952 LOG_REQUEST_END_DATA::ID => LOG_REQUEST_END_DATA::EXTRA_CRC,
33953 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => GIMBAL_MANAGER_SET_PITCHYAW_DATA::EXTRA_CRC,
33954 UAVCAN_NODE_INFO_DATA::ID => UAVCAN_NODE_INFO_DATA::EXTRA_CRC,
33955 GPS_RTK_DATA::ID => GPS_RTK_DATA::EXTRA_CRC,
33956 MISSION_REQUEST_INT_DATA::ID => MISSION_REQUEST_INT_DATA::EXTRA_CRC,
33957 PING_DATA::ID => PING_DATA::EXTRA_CRC,
33958 DEBUG_FLOAT_ARRAY_DATA::ID => DEBUG_FLOAT_ARRAY_DATA::EXTRA_CRC,
33959 SETUP_SIGNING_DATA::ID => SETUP_SIGNING_DATA::EXTRA_CRC,
33960 CAMERA_IMAGE_CAPTURED_DATA::ID => CAMERA_IMAGE_CAPTURED_DATA::EXTRA_CRC,
33961 BATTERY_STATUS_DATA::ID => BATTERY_STATUS_DATA::EXTRA_CRC,
33962 MISSION_COUNT_DATA::ID => MISSION_COUNT_DATA::EXTRA_CRC,
33963 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => OPEN_DRONE_ID_ARM_STATUS_DATA::EXTRA_CRC,
33964 RC_CHANNELS_OVERRIDE_DATA::ID => RC_CHANNELS_OVERRIDE_DATA::EXTRA_CRC,
33965 TERRAIN_REQUEST_DATA::ID => TERRAIN_REQUEST_DATA::EXTRA_CRC,
33966 OBSTACLE_DISTANCE_DATA::ID => OBSTACLE_DISTANCE_DATA::EXTRA_CRC,
33967 LANDING_TARGET_DATA::ID => LANDING_TARGET_DATA::EXTRA_CRC,
33968 FOLLOW_TARGET_DATA::ID => FOLLOW_TARGET_DATA::EXTRA_CRC,
33969 GLOBAL_POSITION_INT_COV_DATA::ID => GLOBAL_POSITION_INT_COV_DATA::EXTRA_CRC,
33970 CONTROL_SYSTEM_STATE_DATA::ID => CONTROL_SYSTEM_STATE_DATA::EXTRA_CRC,
33971 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::EXTRA_CRC,
33972 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::EXTRA_CRC,
33973 HIL_OPTICAL_FLOW_DATA::ID => HIL_OPTICAL_FLOW_DATA::EXTRA_CRC,
33974 VISION_SPEED_ESTIMATE_DATA::ID => VISION_SPEED_ESTIMATE_DATA::EXTRA_CRC,
33975 CAMERA_FOV_STATUS_DATA::ID => CAMERA_FOV_STATUS_DATA::EXTRA_CRC,
33976 MISSION_ITEM_REACHED_DATA::ID => MISSION_ITEM_REACHED_DATA::EXTRA_CRC,
33977 LOGGING_DATA_DATA::ID => LOGGING_DATA_DATA::EXTRA_CRC,
33978 ONBOARD_COMPUTER_STATUS_DATA::ID => ONBOARD_COMPUTER_STATUS_DATA::EXTRA_CRC,
33979 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::EXTRA_CRC,
33980 WHEEL_DISTANCE_DATA::ID => WHEEL_DISTANCE_DATA::EXTRA_CRC,
33981 PARAM_EXT_VALUE_DATA::ID => PARAM_EXT_VALUE_DATA::EXTRA_CRC,
33982 RC_CHANNELS_SCALED_DATA::ID => RC_CHANNELS_SCALED_DATA::EXTRA_CRC,
33983 ATTITUDE_TARGET_DATA::ID => ATTITUDE_TARGET_DATA::EXTRA_CRC,
33984 ATTITUDE_QUATERNION_DATA::ID => ATTITUDE_QUATERNION_DATA::EXTRA_CRC,
33985 HIL_STATE_DATA::ID => HIL_STATE_DATA::EXTRA_CRC,
33986 AUTOPILOT_VERSION_DATA::ID => AUTOPILOT_VERSION_DATA::EXTRA_CRC,
33987 UAVCAN_NODE_STATUS_DATA::ID => UAVCAN_NODE_STATUS_DATA::EXTRA_CRC,
33988 HIL_ACTUATOR_CONTROLS_DATA::ID => HIL_ACTUATOR_CONTROLS_DATA::EXTRA_CRC,
33989 MISSION_ITEM_DATA::ID => MISSION_ITEM_DATA::EXTRA_CRC,
33990 UTM_GLOBAL_POSITION_DATA::ID => UTM_GLOBAL_POSITION_DATA::EXTRA_CRC,
33991 COMMAND_ACK_DATA::ID => COMMAND_ACK_DATA::EXTRA_CRC,
33992 WIND_COV_DATA::ID => WIND_COV_DATA::EXTRA_CRC,
33993 DEBUG_DATA::ID => DEBUG_DATA::EXTRA_CRC,
33994 LOGGING_ACK_DATA::ID => LOGGING_ACK_DATA::EXTRA_CRC,
33995 AVAILABLE_MODES_DATA::ID => AVAILABLE_MODES_DATA::EXTRA_CRC,
33996 STORAGE_INFORMATION_DATA::ID => STORAGE_INFORMATION_DATA::EXTRA_CRC,
33997 CAMERA_TRACKING_GEO_STATUS_DATA::ID => CAMERA_TRACKING_GEO_STATUS_DATA::EXTRA_CRC,
33998 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => OPEN_DRONE_ID_AUTHENTICATION_DATA::EXTRA_CRC,
33999 ODOMETRY_DATA::ID => ODOMETRY_DATA::EXTRA_CRC,
34000 SYSTEM_TIME_DATA::ID => SYSTEM_TIME_DATA::EXTRA_CRC,
34001 VICON_POSITION_ESTIMATE_DATA::ID => VICON_POSITION_ESTIMATE_DATA::EXTRA_CRC,
34002 CAN_FILTER_MODIFY_DATA::ID => CAN_FILTER_MODIFY_DATA::EXTRA_CRC,
34003 OPTICAL_FLOW_RAD_DATA::ID => OPTICAL_FLOW_RAD_DATA::EXTRA_CRC,
34004 SMART_BATTERY_INFO_DATA::ID => SMART_BATTERY_INFO_DATA::EXTRA_CRC,
34005 PARAM_REQUEST_LIST_DATA::ID => PARAM_REQUEST_LIST_DATA::EXTRA_CRC,
34006 LINK_NODE_STATUS_DATA::ID => LINK_NODE_STATUS_DATA::EXTRA_CRC,
34007 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => OPEN_DRONE_ID_OPERATOR_ID_DATA::EXTRA_CRC,
34008 NAMED_VALUE_INT_DATA::ID => NAMED_VALUE_INT_DATA::EXTRA_CRC,
34009 BATTERY_INFO_DATA::ID => BATTERY_INFO_DATA::EXTRA_CRC,
34010 GPS_GLOBAL_ORIGIN_DATA::ID => GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
34011 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
34012 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::EXTRA_CRC
34013 }
34014 HIL_STATE_QUATERNION_DATA::ID => HIL_STATE_QUATERNION_DATA::EXTRA_CRC,
34015 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::EXTRA_CRC,
34016 VIDEO_STREAM_STATUS_DATA::ID => VIDEO_STREAM_STATUS_DATA::EXTRA_CRC,
34017 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
34018 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::EXTRA_CRC
34019 }
34020 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => SET_POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
34021 PARAM_EXT_ACK_DATA::ID => PARAM_EXT_ACK_DATA::EXTRA_CRC,
34022 SAFETY_SET_ALLOWED_AREA_DATA::ID => SAFETY_SET_ALLOWED_AREA_DATA::EXTRA_CRC,
34023 COMMAND_LONG_DATA::ID => COMMAND_LONG_DATA::EXTRA_CRC,
34024 MOUNT_ORIENTATION_DATA::ID => MOUNT_ORIENTATION_DATA::EXTRA_CRC,
34025 POWER_STATUS_DATA::ID => POWER_STATUS_DATA::EXTRA_CRC,
34026 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => CHANGE_OPERATOR_CONTROL_ACK_DATA::EXTRA_CRC,
34027 GPS_RAW_INT_DATA::ID => GPS_RAW_INT_DATA::EXTRA_CRC,
34028 SIM_STATE_DATA::ID => SIM_STATE_DATA::EXTRA_CRC,
34029 CELLULAR_CONFIG_DATA::ID => CELLULAR_CONFIG_DATA::EXTRA_CRC,
34030 LOCAL_POSITION_NED_DATA::ID => LOCAL_POSITION_NED_DATA::EXTRA_CRC,
34031 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => CAMERA_TRACKING_IMAGE_STATUS_DATA::EXTRA_CRC,
34032 TUNNEL_DATA::ID => TUNNEL_DATA::EXTRA_CRC,
34033 RC_CHANNELS_DATA::ID => RC_CHANNELS_DATA::EXTRA_CRC,
34034 NAMED_VALUE_FLOAT_DATA::ID => NAMED_VALUE_FLOAT_DATA::EXTRA_CRC,
34035 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => SET_ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
34036 POSITION_TARGET_LOCAL_NED_DATA::ID => POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
34037 MEMORY_VECT_DATA::ID => MEMORY_VECT_DATA::EXTRA_CRC,
34038 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::EXTRA_CRC,
34039 POSITION_TARGET_GLOBAL_INT_DATA::ID => POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC,
34040 BUTTON_CHANGE_DATA::ID => BUTTON_CHANGE_DATA::EXTRA_CRC,
34041 LOGGING_DATA_ACKED_DATA::ID => LOGGING_DATA_ACKED_DATA::EXTRA_CRC,
34042 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::EXTRA_CRC,
34043 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => GIMBAL_DEVICE_SET_ATTITUDE_DATA::EXTRA_CRC,
34044 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::EXTRA_CRC,
34045 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
34046 TRAJECTORY_REPRESENTATION_BEZIER_DATA::EXTRA_CRC
34047 }
34048 MAG_CAL_REPORT_DATA::ID => MAG_CAL_REPORT_DATA::EXTRA_CRC,
34049 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::EXTRA_CRC,
34050 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::EXTRA_CRC,
34051 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::EXTRA_CRC,
34052 VIDEO_STREAM_INFORMATION_DATA::ID => VIDEO_STREAM_INFORMATION_DATA::EXTRA_CRC,
34053 VIBRATION_DATA::ID => VIBRATION_DATA::EXTRA_CRC,
34054 WIFI_CONFIG_AP_DATA::ID => WIFI_CONFIG_AP_DATA::EXTRA_CRC,
34055 MISSION_REQUEST_LIST_DATA::ID => MISSION_REQUEST_LIST_DATA::EXTRA_CRC,
34056 RAW_RPM_DATA::ID => RAW_RPM_DATA::EXTRA_CRC,
34057 PLAY_TUNE_V2_DATA::ID => PLAY_TUNE_V2_DATA::EXTRA_CRC,
34058 SUPPORTED_TUNES_DATA::ID => SUPPORTED_TUNES_DATA::EXTRA_CRC,
34059 REQUEST_EVENT_DATA::ID => REQUEST_EVENT_DATA::EXTRA_CRC,
34060 SCALED_PRESSURE_DATA::ID => SCALED_PRESSURE_DATA::EXTRA_CRC,
34061 SCALED_PRESSURE3_DATA::ID => SCALED_PRESSURE3_DATA::EXTRA_CRC,
34062 GIMBAL_DEVICE_INFORMATION_DATA::ID => GIMBAL_DEVICE_INFORMATION_DATA::EXTRA_CRC,
34063 MISSION_WRITE_PARTIAL_LIST_DATA::ID => MISSION_WRITE_PARTIAL_LIST_DATA::EXTRA_CRC,
34064 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::EXTRA_CRC,
34065 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::EXTRA_CRC,
34066 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
34067 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::EXTRA_CRC
34068 }
34069 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
34070 SET_POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC
34071 }
34072 _ => 0,
34073 }
34074 }
34075 fn target_system_id(&self) -> Option<u8> {
34076 match self {
34077 Self::V2_EXTENSION(inner) => Some(inner.target_system),
34078 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_system),
34079 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_system),
34080 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_system),
34081 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_system),
34082 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_system),
34083 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_system),
34084 Self::COMMAND_INT(inner) => Some(inner.target_system),
34085 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_system),
34086 Self::SET_MODE(inner) => Some(inner.target_system),
34087 Self::TIMESYNC(inner) => Some(inner.target_system),
34088 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_system),
34089 Self::CAN_FRAME(inner) => Some(inner.target_system),
34090 Self::MISSION_REQUEST(inner) => Some(inner.target_system),
34091 Self::CANFD_FRAME(inner) => Some(inner.target_system),
34092 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_system),
34093 Self::COMMAND_CANCEL(inner) => Some(inner.target_system),
34094 Self::MISSION_ITEM_INT(inner) => Some(inner.target_system),
34095 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_system),
34096 Self::GPS_INJECT_DATA(inner) => Some(inner.target_system),
34097 Self::PARAM_MAP_RC(inner) => Some(inner.target_system),
34098 Self::SERIAL_CONTROL(inner) => Some(inner.target_system),
34099 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_system),
34100 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_system),
34101 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_system),
34102 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_system),
34103 Self::PARAM_SET(inner) => Some(inner.target_system),
34104 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_system),
34105 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_system),
34106 Self::PARAM_EXT_SET(inner) => Some(inner.target_system),
34107 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_system),
34108 Self::MISSION_ACK(inner) => Some(inner.target_system),
34109 Self::SET_HOME_POSITION(inner) => Some(inner.target_system),
34110 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_system),
34111 Self::SET_GPS_GLOBAL_ORIGIN(inner) => Some(inner.target_system),
34112 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_system),
34113 Self::CHANGE_OPERATOR_CONTROL(inner) => Some(inner.target_system),
34114 Self::LOG_REQUEST_END(inner) => Some(inner.target_system),
34115 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_system),
34116 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_system),
34117 Self::PING(inner) => Some(inner.target_system),
34118 Self::SETUP_SIGNING(inner) => Some(inner.target_system),
34119 Self::MISSION_COUNT(inner) => Some(inner.target_system),
34120 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_system),
34121 Self::PLAY_TUNE(inner) => Some(inner.target_system),
34122 Self::LOGGING_DATA(inner) => Some(inner.target_system),
34123 Self::LOG_ERASE(inner) => Some(inner.target_system),
34124 Self::MISSION_ITEM(inner) => Some(inner.target_system),
34125 Self::COMMAND_ACK(inner) => Some(inner.target_system),
34126 Self::LOGGING_ACK(inner) => Some(inner.target_system),
34127 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_system),
34128 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_system),
34129 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_system),
34130 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_system),
34131 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_system),
34132 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_system),
34133 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_system),
34134 Self::COMMAND_LONG(inner) => Some(inner.target_system),
34135 Self::TUNNEL(inner) => Some(inner.target_system),
34136 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_system),
34137 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_system),
34138 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_system),
34139 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_system),
34140 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_system),
34141 Self::PLAY_TUNE_V2(inner) => Some(inner.target_system),
34142 Self::SUPPORTED_TUNES(inner) => Some(inner.target_system),
34143 Self::REQUEST_EVENT(inner) => Some(inner.target_system),
34144 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_system),
34145 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_system),
34146 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_system),
34147 _ => None,
34148 }
34149 }
34150 fn target_component_id(&self) -> Option<u8> {
34151 match self {
34152 Self::V2_EXTENSION(inner) => Some(inner.target_component),
34153 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_component),
34154 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_component),
34155 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_component),
34156 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_component),
34157 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_component),
34158 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_component),
34159 Self::COMMAND_INT(inner) => Some(inner.target_component),
34160 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_component),
34161 Self::TIMESYNC(inner) => Some(inner.target_component),
34162 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_component),
34163 Self::CAN_FRAME(inner) => Some(inner.target_component),
34164 Self::MISSION_REQUEST(inner) => Some(inner.target_component),
34165 Self::CANFD_FRAME(inner) => Some(inner.target_component),
34166 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_component),
34167 Self::COMMAND_CANCEL(inner) => Some(inner.target_component),
34168 Self::MISSION_ITEM_INT(inner) => Some(inner.target_component),
34169 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_component),
34170 Self::GPS_INJECT_DATA(inner) => Some(inner.target_component),
34171 Self::PARAM_MAP_RC(inner) => Some(inner.target_component),
34172 Self::SERIAL_CONTROL(inner) => Some(inner.target_component),
34173 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_component),
34174 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_component),
34175 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_component),
34176 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_component),
34177 Self::PARAM_SET(inner) => Some(inner.target_component),
34178 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_component),
34179 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_component),
34180 Self::PARAM_EXT_SET(inner) => Some(inner.target_component),
34181 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_component),
34182 Self::MISSION_ACK(inner) => Some(inner.target_component),
34183 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_component),
34184 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_component),
34185 Self::LOG_REQUEST_END(inner) => Some(inner.target_component),
34186 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_component),
34187 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_component),
34188 Self::PING(inner) => Some(inner.target_component),
34189 Self::SETUP_SIGNING(inner) => Some(inner.target_component),
34190 Self::MISSION_COUNT(inner) => Some(inner.target_component),
34191 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_component),
34192 Self::PLAY_TUNE(inner) => Some(inner.target_component),
34193 Self::LOGGING_DATA(inner) => Some(inner.target_component),
34194 Self::LOG_ERASE(inner) => Some(inner.target_component),
34195 Self::MISSION_ITEM(inner) => Some(inner.target_component),
34196 Self::COMMAND_ACK(inner) => Some(inner.target_component),
34197 Self::LOGGING_ACK(inner) => Some(inner.target_component),
34198 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_component),
34199 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_component),
34200 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_component),
34201 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_component),
34202 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_component),
34203 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_component),
34204 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_component),
34205 Self::COMMAND_LONG(inner) => Some(inner.target_component),
34206 Self::TUNNEL(inner) => Some(inner.target_component),
34207 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_component),
34208 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_component),
34209 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_component),
34210 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_component),
34211 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_component),
34212 Self::PLAY_TUNE_V2(inner) => Some(inner.target_component),
34213 Self::SUPPORTED_TUNES(inner) => Some(inner.target_component),
34214 Self::REQUEST_EVENT(inner) => Some(inner.target_component),
34215 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_component),
34216 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_component),
34217 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_component),
34218 _ => None,
34219 }
34220 }
34221}